diff --git a/Bilder/Anpassungen.png b/Bilder/Anpassungen.png
new file mode 100644
index 0000000000000000000000000000000000000000..74ab8d396750716b56bbf483ee1fe056c905972f
Binary files /dev/null and b/Bilder/Anpassungen.png differ
diff --git a/Bilder/Klassendiagramm_Line_Follower_Node.png b/Bilder/Klassendiagramm_Line_Follower_Node.png
new file mode 100644
index 0000000000000000000000000000000000000000..c6ba7cde094c4e42ab3dc5bbb11ad5f15c2c30b6
Binary files /dev/null and b/Bilder/Klassendiagramm_Line_Follower_Node.png differ
diff --git a/Bilder/SSH.png b/Bilder/SSH.png
new file mode 100644
index 0000000000000000000000000000000000000000..2d586187104ae1b48ff7da77937e8d0ca9aba950
Binary files /dev/null and b/Bilder/SSH.png differ
diff --git a/Bilder/Sensoren.jpg b/Bilder/Sensoren.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..89810e33d2e9cf7bbceac6c67860d495138f2c3e
Binary files /dev/null and b/Bilder/Sensoren.jpg differ
diff --git a/Bilder/acht.mp4 b/Bilder/acht.mp4
new file mode 100644
index 0000000000000000000000000000000000000000..6fff2af9abc03970275d5ca180d02adcd360353a
Binary files /dev/null and b/Bilder/acht.mp4 differ
diff --git a/Bilder/algorithmus.jpg b/Bilder/algorithmus.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..0edc9970b6aa00f94ffe5fcbe93efef515239365
Binary files /dev/null and b/Bilder/algorithmus.jpg differ
diff --git a/Bilder/entrypoint.png b/Bilder/entrypoint.png
new file mode 100644
index 0000000000000000000000000000000000000000..5a45bec3308b42aac37e8c98df7e17af96e610ab
Binary files /dev/null and b/Bilder/entrypoint.png differ
diff --git a/Bilder/explosionsdarstellung.mp4 b/Bilder/explosionsdarstellung.mp4
new file mode 100644
index 0000000000000000000000000000000000000000..2838de8bba399b160134bf68f1fd85d5444db48d
Binary files /dev/null and b/Bilder/explosionsdarstellung.mp4 differ
diff --git a/Bilder/filezilla.png b/Bilder/filezilla.png
new file mode 100644
index 0000000000000000000000000000000000000000..65b417800392e43a4b6ffafde12880413f948d58
Binary files /dev/null and b/Bilder/filezilla.png differ
diff --git a/Bilder/firmware_checken.png b/Bilder/firmware_checken.png
new file mode 100644
index 0000000000000000000000000000000000000000..91da0ab7a4fbd4ab557466b7a0e5ee9b941224a5
Binary files /dev/null and b/Bilder/firmware_checken.png differ
diff --git a/Bilder/frontal.jpg b/Bilder/frontal.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..099ce7480b528fc4c0e498ff65de33f42000c3d9
Binary files /dev/null and b/Bilder/frontal.jpg differ
diff --git a/Bilder/igmr.png b/Bilder/igmr.png
new file mode 100644
index 0000000000000000000000000000000000000000..57cefb51792af78350ff4de1822b3a8d64ba836a
Binary files /dev/null and b/Bilder/igmr.png differ
diff --git a/Bilder/komponenten.jpg b/Bilder/komponenten.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..5da525ec1e656ff4315416e3d3adc2e1ce50b6c1
Binary files /dev/null and b/Bilder/komponenten.jpg differ
diff --git a/Bilder/linie_folgen_2S.mp4 b/Bilder/linie_folgen_2S.mp4
new file mode 100644
index 0000000000000000000000000000000000000000..4f9baac9875c0f14c21084f315332c996c817bfc
Binary files /dev/null and b/Bilder/linie_folgen_2S.mp4 differ
diff --git a/Bilder/paket.png b/Bilder/paket.png
new file mode 100644
index 0000000000000000000000000000000000000000..53c12d18ed8e0a61d91b98ee7f84b6ee2ad4dd7c
Binary files /dev/null and b/Bilder/paket.png differ
diff --git a/Bilder/pi_imager.png b/Bilder/pi_imager.png
new file mode 100644
index 0000000000000000000000000000000000000000..dac5213d97b350fa2d03e9209dacc3c22f9a4d13
Binary files /dev/null and b/Bilder/pi_imager.png differ
diff --git a/Bilder/pico-gpio.png b/Bilder/pico-gpio.png
new file mode 100644
index 0000000000000000000000000000000000000000..fc11569222fe6e4512d91269b9fe4f8e748e0fb8
Binary files /dev/null and b/Bilder/pico-gpio.png differ
diff --git a/Bilder/raspi4-gpio.png b/Bilder/raspi4-gpio.png
new file mode 100644
index 0000000000000000000000000000000000000000..24238cc23d89f18fca2bc5daa5e3f62abc4c4390
Binary files /dev/null and b/Bilder/raspi4-gpio.png differ
diff --git a/Bilder/render 6.jpg b/Bilder/render 6.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..7045d26cf896eb20eb1fd01caaa700f3bea67970
Binary files /dev/null and b/Bilder/render 6.jpg differ
diff --git a/Bilder/ros_architektur.jpg b/Bilder/ros_architektur.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..bd09f8e5644da1a593d9a2a0a253ab9a03402654
Binary files /dev/null and b/Bilder/ros_architektur.jpg differ
diff --git a/Bilder/seitlich.jpg b/Bilder/seitlich.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..ac99ffd254202a4a153990e7dc3324720196e117
Binary files /dev/null and b/Bilder/seitlich.jpg differ
diff --git a/Bilder/sensoreinhausung.jpg b/Bilder/sensoreinhausung.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..efa73f393bc50f75ad90c702a21b47790e46afde
Binary files /dev/null and b/Bilder/sensoreinhausung.jpg differ
diff --git a/Bilder/sensoreinhausung_offen.jpg b/Bilder/sensoreinhausung_offen.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..51f0f050d1aa261888c2d89c1be0f5caafb539cb
Binary files /dev/null and b/Bilder/sensoreinhausung_offen.jpg differ
diff --git a/Bilder/systemstruktur.jpg b/Bilder/systemstruktur.jpg
new file mode 100644
index 0000000000000000000000000000000000000000..b17cd47e086202b9ac773d5a8c2303b57bfbd8d4
Binary files /dev/null and b/Bilder/systemstruktur.jpg differ
diff --git a/Bilder/thonny_interpreter.png b/Bilder/thonny_interpreter.png
new file mode 100644
index 0000000000000000000000000000000000000000..e27679181bc2246a46d299f69624d206f06dde80
Binary files /dev/null and b/Bilder/thonny_interpreter.png differ
diff --git a/Bilder/turtlebot-setup.png b/Bilder/turtlebot-setup.png
new file mode 100644
index 0000000000000000000000000000000000000000..f36f77016028cd035ae9f89086749fbfb2728db5
Binary files /dev/null and b/Bilder/turtlebot-setup.png differ
diff --git a/Bilder/wifi-setup.png b/Bilder/wifi-setup.png
new file mode 100644
index 0000000000000000000000000000000000000000..cdb94405bdd82a67e1bca30f1e7e6f91cdaed5a2
Binary files /dev/null and b/Bilder/wifi-setup.png differ
diff --git a/Code/Pico(Micropython)/TCRT5000.py b/Code/Pico(Micropython)/TCRT5000.py
new file mode 100644
index 0000000000000000000000000000000000000000..eafd7104f4e9e3a03798f9b96ff87f7879180199
--- /dev/null
+++ b/Code/Pico(Micropython)/TCRT5000.py
@@ -0,0 +1,35 @@
+# Auslesen zweier TCRT5000 Liniensensoren mit eimem Raspberry Pi Pico und Micropython
+
+
+from machine import Pin
+from time import sleep
+
+# Pin-Nummern für die Sensoren
+LEFT_PIN = 16  # OUT-Pin des linken Sensors, GPIO16
+RIGHT_PIN = 17  # OUT-Pin des rechten Sensors, GPIO17
+
+# Sensoren initialisieren
+left_sensor = Pin(LEFT_PIN, Pin.IN)
+right_sensor = Pin(RIGHT_PIN, Pin.IN)
+
+try:
+    while True:
+        # Sensor-Ausgang lesen
+        left_value = left_sensor.value()
+        right_value = right_sensor.value()
+
+        if left_value == 1:
+            print("LINKS: 1 -> schwarz")
+        else:
+            print("LINKS: 0 -> hell")
+
+        if right_value == 1:
+            print("RECHTS: 1 -> schwarz")
+        else:
+            print("RECHTS: 0 -> hell")
+
+        # Verzögerung für bessere Lesbarkeit
+        sleep(0.3)
+
+except KeyboardInterrupt:
+    print("Programm beendet")
diff --git a/Code/Pico(Micropython)/externe_led.py b/Code/Pico(Micropython)/externe_led.py
new file mode 100644
index 0000000000000000000000000000000000000000..701eba991ae9febe5b14400e248b8d7922dfd52d
--- /dev/null
+++ b/Code/Pico(Micropython)/externe_led.py
@@ -0,0 +1,14 @@
+# Code in Micropython für den Raspberry Pi Pico
+# Importieren der notwendigen Module
+from machine import Pin
+from time import sleep
+
+# Initialisierung der LED (Pin-Nummer anpassen, falls notwendig)
+led = Pin(1, Pin.OUT)  # Pin 1 steuert die eingebaute LED des Raspberry Pi Pico
+
+# Endlosschleife zum Blinken der LED
+while True:
+    led.value(1)  # LED einschalten
+    sleep(0.5)    # 0,5 Sekunden warten
+    led.value(0)  # LED ausschalten
+    sleep(0.5)    # 0,5 Sekunden warten
diff --git a/Code/Pico(Micropython)/hc_sr04.py b/Code/Pico(Micropython)/hc_sr04.py
new file mode 100644
index 0000000000000000000000000000000000000000..478e565f0f30716dc84b6905fb3d98803ea247ec
--- /dev/null
+++ b/Code/Pico(Micropython)/hc_sr04.py
@@ -0,0 +1,39 @@
+# Code in Micropython für den Raspberry Pi Pico
+
+from machine import Pin, time_pulse_us
+import time
+
+# Pin-Definitionen
+TRIG_PIN = 27  # GPIO-Pin für Trig
+ECHO_PIN = 26  # GPIO-Pin für Echo
+
+# Initialisierung der Pins
+trig = Pin(TRIG_PIN, Pin.OUT)
+echo = Pin(ECHO_PIN, Pin.IN)
+
+def measure_distance():
+    # Trigger-Puls erzeugen
+    trig.low()
+    time.sleep_us(2)
+    trig.high()
+    time.sleep_us(10)
+    trig.low()
+
+    # Zeit messen, wie lange das Echo ankommt
+    try:
+        duration = time_pulse_us(echo, 1, 30000)  # Timeout nach 30ms
+    except OSError:  # Wenn kein Signal zurückkommt
+        return -1
+
+    # Entfernung berechnen (Schallgeschwindigkeit = 343 m/s)
+    distance = (duration * 0.0343) / 2  # Zeit in cm umrechnen
+    return distance
+
+# Hauptprogramm
+while True:
+    distance = measure_distance()
+    if distance == -1:
+        print("Kein Signal")
+    else:
+        print("Entfernung: {:.2f} cm".format(distance))
+    time.sleep(1)
diff --git a/Code/Pico(Micropython)/interne_led.py b/Code/Pico(Micropython)/interne_led.py
new file mode 100644
index 0000000000000000000000000000000000000000..a923c8d6decef1adabd757d17abcebec62530819
--- /dev/null
+++ b/Code/Pico(Micropython)/interne_led.py
@@ -0,0 +1,14 @@
+# Dieser Code in Micropyhton ist für den Raspberry Pi Pico gedacht
+# und lässt die interne LED des Picos (auf GPIO 25) blinken.
+
+import machine
+import time
+
+# Initialisiere den GPIO-Pin 25 (eingebaute LED)
+led = machine.Pin(25, machine.Pin.OUT)
+
+while True:
+    led.value(1)  # LED einschalten
+    time.sleep(0.5)  # 500 ms warten
+    led.value(0)  # LED ausschalten
+    time.sleep(0.5)  # 500 ms warten
diff --git a/Code/Pico(Micropython)/sensor_bridge_1.py b/Code/Pico(Micropython)/sensor_bridge_1.py
new file mode 100644
index 0000000000000000000000000000000000000000..fde81a221d1e9dd22ef983e91a28e60bd05609f1
--- /dev/null
+++ b/Code/Pico(Micropython)/sensor_bridge_1.py
@@ -0,0 +1,31 @@
+# Skript in Micropython für den Raspberry Pi Pico
+# Liest die Sensorwerte zweier Liniensensoren aus und
+# gibt die Ergebnisse über USB (seriellen Ausgang) aus
+
+
+from machine import Pin
+from time import sleep
+import sys
+
+# Pin-Nummern für die Sensoren
+LEFT_PIN = 7  # GPIO7 für linken Sensor
+RIGHT_PIN = 8  # GPIO8 für rechten Sensor
+
+# Initialisiere die Pins für die Sensoren
+left_sensor = Pin(LEFT_PIN, Pin.IN)
+right_sensor = Pin(RIGHT_PIN, Pin.IN)
+
+try:
+    while True:
+        # Sensor-Werte auslesen
+        left_value = left_sensor.value()
+        right_value = right_sensor.value()
+
+        # Daten als JSON-ähnliches Format senden
+        sys.stdout.write(f"{left_value},{right_value}\n")
+
+        # Verzögerung, um Daten lesbar zu machen
+        sleep(0.1)
+
+except KeyboardInterrupt:
+    print("Programm beendet")
\ No newline at end of file
diff --git a/Code/Pico(Micropython)/sensor_bridge_2.py b/Code/Pico(Micropython)/sensor_bridge_2.py
new file mode 100644
index 0000000000000000000000000000000000000000..99ad27a775bda84ce682ffa29878c5a1f7ac973f
--- /dev/null
+++ b/Code/Pico(Micropython)/sensor_bridge_2.py
@@ -0,0 +1,61 @@
+# Skript in Micropython für den Raspberry Pi Pico
+# Liest die Sensorwerte von fünf Liniensensoren und dem HC-SR 04 aus und
+# gibt die Ergebnisse über USB (seriellem Ausgang) aus
+
+from machine import Pin, time_pulse_us
+from time import sleep
+import sys
+
+# Pin-Nummern für die Sensoren
+SENSOR_PINS = [13,8,11,7,4]  # OUT-Pins der fünf Liniensensoren in der Reihenfolge von rechts nach links
+TRIG_PIN = 26
+ECHO_PIN = 19
+
+
+# Sensoren initialisieren
+sensors = [Pin(pin, Pin.IN) for pin in SENSOR_PINS]
+
+trig = Pin(TRIG_PIN, Pin.OUT)
+echo = Pin(ECHO_PIN, Pin.IN)
+
+
+def measure_distance():
+    # Sende ein 10 µs langes HIGH-Signal über den Trigger
+    trig.low()
+    sleep(0.02)  # Sicherstellen, dass Trigger vorher LOW war
+    trig.high()
+    sleep(0.00001)  # 10 µs
+    trig.low()
+
+    # Warte auf das HIGH-Signal vom Echo und messe die Dauer
+    pulse_duration = time_pulse_us(echo, 1, 30000)  # Timeout nach 30 ms (30000 µs)
+
+    # Berechne die Distanz (Schallgeschwindigkeit: 34300 cm/s)
+    distance = (pulse_duration / 2) * 0.0343  # Hin- und Rückweg berücksichtigen
+
+    return distance
+
+try:
+    while True:
+        messung = ""
+        
+        distance = measure_distance()
+        
+        for i, sensor in enumerate(sensors):
+            value = sensor.value()
+            messung += str(value)
+            messung += ","
+        
+        messung += str(distance)
+        messung += "\n"
+        
+        # print(messung)
+        
+        sys.stdout.write(messung)
+        
+        # Verzögerung für bessere Lesbarkeit
+        sleep(0.05)
+
+except KeyboardInterrupt:
+    print("Programm beendet")
+
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/line_follower_pkg/__init__.py b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/line_follower_pkg/__init__.py
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/line_follower_pkg/line_follower_node.py b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/line_follower_pkg/line_follower_node.py
new file mode 100644
index 0000000000000000000000000000000000000000..fc79e24a292378d3735b44a0aaa7d0645d216b3f
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/line_follower_pkg/line_follower_node.py
@@ -0,0 +1,71 @@
+import rclpy
+from rclpy.node import Node
+from geometry_msgs.msg import Twist
+from std_msgs.msg import String
+
+class LineFollowerNode(Node):
+    def __init__(self):
+        super().__init__('line_follower')
+        
+        # Abonnieren der Pico-Daten
+        self.sensor_subscription = self.create_subscription(
+            String,
+            'pico_data',  # Topic für die Pico-Daten
+            self.sensor_callback,
+            10)
+        
+        # Publisher für Bewegungsbefehle
+        self.cmd_publisher = self.create_publisher(Twist, '/cmd_vel', 10)
+
+        # Initialisierung der Steuerungsvariablen
+        self.left_sensor = 0.0
+        self.right_sensor = 0.0
+
+    def sensor_callback(self, msg):
+        try:
+            # Verarbeiten der Sensordaten aus der Nachricht
+            data = msg.data.split(',')  # Annahme: Daten sind als "Wert1,Wert2" formatiert
+            self.left_sensor = float(data[0])  # Linker Sensorwert
+            self.right_sensor = float(data[1])  # Rechter Sensorwert
+            self.get_logger().info(f"Left: {self.left_sensor}, Right: {self.right_sensor}")
+            
+            # Linie folgen
+            self.follow_line()
+        except (ValueError, IndexError) as e:
+            self.get_logger().error(f"Fehler beim Verarbeiten der Sensordaten: {e}")
+
+    def follow_line(self):
+        twist_msg = Twist()
+
+        if self.left_sensor > self.right_sensor:
+            # Drehe nach links
+            twist_msg.linear.x = 0.02
+            twist_msg.angular.z = 0.5
+            self.get_logger().info(f"Links: {self.left_sensor}, Rechts: {self.right_sensor} - L > R - Drehe nach links")
+        elif self.right_sensor > self.left_sensor:
+            # Drehe nach rechts
+            twist_msg.linear.x = 0.02
+            twist_msg.angular.z = -0.5
+            self.get_logger().info(f"Links: {self.left_sensor}, Rechts: {self.right_sensor} - L < R - Drehe nach rechts")
+        else:
+            # Geradeaus fahren
+            twist_msg.linear.x = 0.05
+            twist_msg.angular.z = 0.0
+            self.get_logger().info(f"Links: {self.left_sensor}, Rechts: {self.right_sensor} - L = R - Fahre geradeaus")
+
+        # Bewegungsbefehle senden
+        self.cmd_publisher.publish(twist_msg)
+
+def main(args=None):
+    rclpy.init(args=args)
+    node = LineFollowerNode()
+    try:
+        rclpy.spin(node)
+    except KeyboardInterrupt:
+        pass
+    finally:
+        node.destroy_node()
+        rclpy.shutdown()
+
+if __name__ == '__main__':
+    main()
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/package.xml b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/package.xml
new file mode 100644
index 0000000000000000000000000000000000000000..80bce246184f93e3a77a395e4f0c5fedae37af48
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/package.xml
@@ -0,0 +1,21 @@
+<?xml version="1.0"?>
+<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
+<package format="3">
+  <name>line_follower_pkg</name>
+  <version>0.0.0</version>
+  <description>TODO: Package description</description>
+  <maintainer email="turtlebot@todo.todo">turtlebot</maintainer>
+  <license>TODO: License declaration</license>
+
+  <depend>rclpy</depend>
+  <depend>std_msgs</depend>
+
+  <test_depend>ament_copyright</test_depend>
+  <test_depend>ament_flake8</test_depend>
+  <test_depend>ament_pep257</test_depend>
+  <test_depend>python3-pytest</test_depend>
+
+  <export>
+    <build_type>ament_python</build_type>
+  </export>
+</package>
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/resource/line_follower_pkg b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/resource/line_follower_pkg
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/setup.cfg b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/setup.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..2d13ad284e4de749091d311ddbcaea95d8091d40
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/setup.cfg
@@ -0,0 +1,4 @@
+[develop]
+script_dir=$base/lib/line_follower_pkg
+[install]
+install_scripts=$base/lib/line_follower_pkg
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/setup.py b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/setup.py
new file mode 100644
index 0000000000000000000000000000000000000000..26d6a4fda441ceb52684a010d8a7fd309424231b
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/setup.py
@@ -0,0 +1,26 @@
+from setuptools import find_packages, setup
+
+package_name = 'line_follower_pkg'
+
+setup(
+    name=package_name,
+    version='0.0.0',
+    packages=find_packages(exclude=['test']),
+    data_files=[
+        ('share/ament_index/resource_index/packages',
+            ['resource/' + package_name]),
+        ('share/' + package_name, ['package.xml']),
+    ],
+    install_requires=['setuptools'],
+    zip_safe=True,
+    maintainer='turtlebot',
+    maintainer_email='turtlebot@todo.todo',
+    description='TODO: Package description',
+    license='TODO: License declaration',
+    tests_require=['pytest'],
+    entry_points={
+        'console_scripts': [
+		'line_follower_node = line_follower_pkg.line_follower_node:main',
+        ],
+    },
+)
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/test/test_copyright.py b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/test/test_copyright.py
new file mode 100644
index 0000000000000000000000000000000000000000..97a39196e84db97954341162a6d2e7f771d938c0
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/test/test_copyright.py
@@ -0,0 +1,25 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_copyright.main import main
+import pytest
+
+
+# Remove the `skip` decorator once the source file(s) have a copyright header
+@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
+@pytest.mark.copyright
+@pytest.mark.linter
+def test_copyright():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found errors'
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/test/test_flake8.py b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/test/test_flake8.py
new file mode 100644
index 0000000000000000000000000000000000000000..27ee1078ff077cc3a0fec75b7d023101a68164d1
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/test/test_flake8.py
@@ -0,0 +1,25 @@
+# Copyright 2017 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_flake8.main import main_with_errors
+import pytest
+
+
+@pytest.mark.flake8
+@pytest.mark.linter
+def test_flake8():
+    rc, errors = main_with_errors(argv=[])
+    assert rc == 0, \
+        'Found %d code style errors / warnings:\n' % len(errors) + \
+        '\n'.join(errors)
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/test/test_pep257.py b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/test/test_pep257.py
new file mode 100644
index 0000000000000000000000000000000000000000..b234a3840f4c5bd38f043638c8622b8f240e1185
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/line_follower_pkg/test/test_pep257.py
@@ -0,0 +1,23 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_pep257.main import main
+import pytest
+
+
+@pytest.mark.linter
+@pytest.mark.pep257
+def test_pep257():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found code style errors / warnings'
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/package.xml b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/package.xml
new file mode 100644
index 0000000000000000000000000000000000000000..f09c1359b3def53e576397710d621e114721a6e7
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/package.xml
@@ -0,0 +1,18 @@
+<?xml version="1.0"?>
+<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
+<package format="3">
+  <name>pico_reader_pkg</name>
+  <version>0.0.0</version>
+  <description>TODO: Package description</description>
+  <maintainer email="turtlebot@todo.todo">turtlebot</maintainer>
+  <license>TODO: License declaration</license>
+
+  <test_depend>ament_copyright</test_depend>
+  <test_depend>ament_flake8</test_depend>
+  <test_depend>ament_pep257</test_depend>
+  <test_depend>python3-pytest</test_depend>
+
+  <export>
+    <build_type>ament_python</build_type>
+  </export>
+</package>
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/pico_reader_pkg/__init__.py b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/pico_reader_pkg/__init__.py
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/pico_reader_pkg/pico_reader_node.py b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/pico_reader_pkg/pico_reader_node.py
new file mode 100644
index 0000000000000000000000000000000000000000..84457f7bf8ae4327bc48aaaab6f8daba811bd47d
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/pico_reader_pkg/pico_reader_node.py
@@ -0,0 +1,48 @@
+import rclpy
+from rclpy.node import Node
+from std_msgs.msg import String
+import serial
+
+class PicoUSBReader(Node):
+    def __init__(self):
+        super().__init__('pico_usb_reader')
+
+        # Publisher für das ROS 2 Topic
+        self.publisher = self.create_publisher(String, 'pico_data', 10)
+
+        # Seriellen Port öffnen (Passe die Port-Adresse ggf. an)
+        try:
+            self.serial_port = serial.Serial('/dev/ttyACM0', baudrate=9600, timeout=1)
+            self.get_logger().info("Verbindung zum Pico hergestellt (USB)")
+        except serial.SerialException as e:
+            self.get_logger().error(f"Konnte seriellen Port nicht öffnen: {e}")
+            self.serial_port = None
+
+        # Timer einrichten, um Daten vom Pico zu lesen
+        self.timer = self.create_timer(0.1, self.read_from_pico)
+
+    def read_from_pico(self):
+        if self.serial_port and self.serial_port.in_waiting > 0:
+            try:
+                data = self.serial_port.readline().decode('utf-8').strip()
+                msg = String()
+                msg.data = data
+                self.publisher.publish(msg)
+                self.get_logger().info(f"{data}")
+            except Exception as e:
+                self.get_logger().error(f"Fehler beim Lesen der Daten: {e}")
+
+def main(args=None):
+    rclpy.init(args=args)
+    node = PicoUSBReader()
+    try:
+        rclpy.spin(node)
+    except KeyboardInterrupt:
+        pass
+    finally:
+        node.destroy_node()
+        rclpy.shutdown()
+
+if __name__ == '__main__':
+    main()
+
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/resource/pico_reader_pkg b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/resource/pico_reader_pkg
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/setup.cfg b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/setup.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..3609d04a475e25ff64b5f0f2098d834ff658a4b0
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/setup.cfg
@@ -0,0 +1,4 @@
+[develop]
+script_dir=$base/lib/pico_reader_pkg
+[install]
+install_scripts=$base/lib/pico_reader_pkg
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/setup.py b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/setup.py
new file mode 100644
index 0000000000000000000000000000000000000000..3d58152e10050bb5c6b8eb9e3b919a5ffc19037d
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/setup.py
@@ -0,0 +1,27 @@
+from setuptools import find_packages, setup
+
+package_name = 'pico_reader_pkg'
+
+setup(
+    name=package_name,
+    version='0.0.0',
+    packages=find_packages(exclude=['test']),
+    data_files=[
+        ('share/ament_index/resource_index/packages',
+         ['resource/' + package_name]),
+        ('share/' + package_name, ['package.xml']),
+    ],
+    install_requires=['setuptools'],
+    zip_safe=True,
+    maintainer='turtlebot',
+    maintainer_email='turtlebot@todo.todo',
+    description='ROS 2 Package for reading data from a Raspberry Pi Pico via USB',
+    license='Apache License 2.0',
+    tests_require=['pytest'],
+    entry_points={
+        'console_scripts': [
+            'pico_reader_node = pico_reader_pkg.pico_reader_node:main',
+        ],
+    },
+)
+
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/test/test_copyright.py b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/test/test_copyright.py
new file mode 100644
index 0000000000000000000000000000000000000000..97a39196e84db97954341162a6d2e7f771d938c0
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/test/test_copyright.py
@@ -0,0 +1,25 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_copyright.main import main
+import pytest
+
+
+# Remove the `skip` decorator once the source file(s) have a copyright header
+@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
+@pytest.mark.copyright
+@pytest.mark.linter
+def test_copyright():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found errors'
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/test/test_flake8.py b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/test/test_flake8.py
new file mode 100644
index 0000000000000000000000000000000000000000..27ee1078ff077cc3a0fec75b7d023101a68164d1
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/test/test_flake8.py
@@ -0,0 +1,25 @@
+# Copyright 2017 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_flake8.main import main_with_errors
+import pytest
+
+
+@pytest.mark.flake8
+@pytest.mark.linter
+def test_flake8():
+    rc, errors = main_with_errors(argv=[])
+    assert rc == 0, \
+        'Found %d code style errors / warnings:\n' % len(errors) + \
+        '\n'.join(errors)
diff --git a/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/test/test_pep257.py b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/test/test_pep257.py
new file mode 100644
index 0000000000000000000000000000000000000000..b234a3840f4c5bd38f043638c8622b8f240e1185
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_2_Sensoren/pico_reader_pkg/test/test_pep257.py
@@ -0,0 +1,23 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_pep257.main import main
+import pytest
+
+
+@pytest.mark.linter
+@pytest.mark.pep257
+def test_pep257():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found code style errors / warnings'
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/README.md b/Code/ROS_Nodes_fuer_5_Sensoren/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..221fe48a0b5e339623f6766da86d53f0c2ee5b51
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/README.md
@@ -0,0 +1,2 @@
+###### Klassendiagramm der *line_follower_node*
+![Klassendiagramm Line Follower Node](/Bilder/Klassendiagramm_Line_Follower_Node.png)
\ No newline at end of file
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/line_follower_pkg/__init__.py b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/line_follower_pkg/__init__.py
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/line_follower_pkg/line_follower_node.py b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/line_follower_pkg/line_follower_node.py
new file mode 100644
index 0000000000000000000000000000000000000000..50418593def2d21f236bdd88ba9f745b700284b5
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/line_follower_pkg/line_follower_node.py
@@ -0,0 +1,123 @@
+import rclpy
+from rclpy.node import Node
+from geometry_msgs.msg import Twist
+from std_msgs.msg import String
+
+
+class LineFollowerNode(Node):
+    def __init__(self):
+        super().__init__('line_follower_node')
+
+        # Publisher für die Steuerung des TurtleBot
+        self.cmd_vel_publisher = self.create_publisher(Twist, '/cmd_vel', 1)
+
+        # Subscriber für die Liniensensor-Daten
+        self.create_subscription(
+            String,
+            'line_sensor_data',
+            self.line_sensor_callback,
+            1
+        )
+
+        # Subscriber für die Frontkollision-Daten
+        self.create_subscription(
+            String,
+            'front_collision_data',
+            self.front_collision_callback,
+            1
+        )
+
+        # Initialisiere Variablen
+        self.line_sensor_data = [0, 0, 0, 0, 0]
+        self.front_collision_distance = float('inf')  # Unendlich groß, kein Hindernis
+
+        # Schwellenwert für die Hinderniserkennung (in cm)
+        self.collision_threshold = 10.0
+
+        self.get_logger().info('Line Follower Node started')
+
+    def line_sensor_callback(self, msg):
+        try:
+            # Liniensensor-Daten als Liste von 1/0 verarbeiten
+            self.line_sensor_data = [int(x) for x in msg.data.split(',')]
+            self.line_sensor_data.reverse()
+            self.get_logger().info(f'Line sensor data: {self.line_sensor_data}')
+            self.control_robot()
+        except ValueError as e:
+            self.get_logger().error(f'Error parsing line sensor data: {e}')
+
+    def front_collision_callback(self, msg):
+        try:
+            # Abstandswert aus der Nachricht extrahieren
+            self.front_collision_distance = float(msg.data)
+            self.get_logger().info(f'Front collision distance: {self.front_collision_distance}')
+        except ValueError as e:
+            self.get_logger().error(f'Error parsing collision data: {e}')
+
+    def control_robot(self):
+        # Erstelle die Steuerungsnachricht
+        twist = Twist()
+
+        # Hindernisvermeidung
+        if self.front_collision_distance < self.collision_threshold and self.front_collision_distance > 0.0:
+            self.get_logger().warn('Obstacle detected! Stopping...')
+            twist.linear.x = 0.0
+            twist.angular.z = 0.0
+            self.cmd_vel_publisher.publish(twist)
+            return
+
+        # Linienverfolgungslogik basierend auf den Liniensensoren
+        # Sensoren: [rechts, mittig-rechts, mittig, mittig-links, links]
+                # Linienverfolgungslogik basierend auf den Liniensensoren
+        # Sensoren: [rechts, mittig-rechts, mittig, mittig-links, links]
+        if self.line_sensor_data[2] == 1 and self.line_sensor_data[1] == 1 and self.line_sensor_data[3] == 1:
+            # Geradeaus
+            twist.linear.x = 0.1
+            twist.angular.z = 0.0
+            self.get_logger().info('Geradeaus')
+        elif self.line_sensor_data[0] == 1:
+            # Voll nach links
+            twist.linear.x = 0.05
+            twist.angular.z = 0.8
+            self.get_logger().info('Hart Links')
+        elif self.line_sensor_data[4] == 1:
+            # Voll nach rechts
+            twist.linear.x = 0.05
+            twist.angular.z = -0.8
+            self.get_logger().info('Hart Rechts')
+        elif self.line_sensor_data[1] == 1:
+            # Nach links
+            twist.linear.x = 0.05
+            twist.angular.z = 0.4
+            self.get_logger().info('Leicht Links')
+        elif self.line_sensor_data[3] == 1:
+            # Nach rechts
+            twist.linear.x = 0.05
+            twist.angular.z = -0.4
+            self.get_logger().info('Leicht Rechts')
+        elif self.line_sensor_data[2] == 1:
+            # Geradeaus
+            twist.linear.x = 0.1
+            twist.angular.z = 0.0
+            self.get_logger().info('Geradeaus')
+        else:
+            # Linie verloren
+            self.get_logger().warn('Line verloren, fahre geradeaus')
+            twist.linear.x = 0.05
+            twist.angular.z = 0.0
+
+        # Steuerungsbefehle veröffentlichen
+        self.cmd_vel_publisher.publish(twist)
+
+def main(args=None):
+    rclpy.init(args=args)
+    node = LineFollowerNode()
+    try:
+        rclpy.spin(node)
+    except KeyboardInterrupt:
+        node.get_logger().info('Node stopped by user')
+    finally:
+        rclpy.shutdown()
+
+if __name__ == '__main__':
+    main()
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/package.xml b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/package.xml
new file mode 100644
index 0000000000000000000000000000000000000000..80bce246184f93e3a77a395e4f0c5fedae37af48
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/package.xml
@@ -0,0 +1,21 @@
+<?xml version="1.0"?>
+<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
+<package format="3">
+  <name>line_follower_pkg</name>
+  <version>0.0.0</version>
+  <description>TODO: Package description</description>
+  <maintainer email="turtlebot@todo.todo">turtlebot</maintainer>
+  <license>TODO: License declaration</license>
+
+  <depend>rclpy</depend>
+  <depend>std_msgs</depend>
+
+  <test_depend>ament_copyright</test_depend>
+  <test_depend>ament_flake8</test_depend>
+  <test_depend>ament_pep257</test_depend>
+  <test_depend>python3-pytest</test_depend>
+
+  <export>
+    <build_type>ament_python</build_type>
+  </export>
+</package>
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/resource/line_follower_pkg b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/resource/line_follower_pkg
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/setup.cfg b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/setup.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..2d13ad284e4de749091d311ddbcaea95d8091d40
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/setup.cfg
@@ -0,0 +1,4 @@
+[develop]
+script_dir=$base/lib/line_follower_pkg
+[install]
+install_scripts=$base/lib/line_follower_pkg
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/setup.py b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/setup.py
new file mode 100644
index 0000000000000000000000000000000000000000..26d6a4fda441ceb52684a010d8a7fd309424231b
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/setup.py
@@ -0,0 +1,26 @@
+from setuptools import find_packages, setup
+
+package_name = 'line_follower_pkg'
+
+setup(
+    name=package_name,
+    version='0.0.0',
+    packages=find_packages(exclude=['test']),
+    data_files=[
+        ('share/ament_index/resource_index/packages',
+            ['resource/' + package_name]),
+        ('share/' + package_name, ['package.xml']),
+    ],
+    install_requires=['setuptools'],
+    zip_safe=True,
+    maintainer='turtlebot',
+    maintainer_email='turtlebot@todo.todo',
+    description='TODO: Package description',
+    license='TODO: License declaration',
+    tests_require=['pytest'],
+    entry_points={
+        'console_scripts': [
+		'line_follower_node = line_follower_pkg.line_follower_node:main',
+        ],
+    },
+)
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/test/test_copyright.py b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/test/test_copyright.py
new file mode 100644
index 0000000000000000000000000000000000000000..97a39196e84db97954341162a6d2e7f771d938c0
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/test/test_copyright.py
@@ -0,0 +1,25 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_copyright.main import main
+import pytest
+
+
+# Remove the `skip` decorator once the source file(s) have a copyright header
+@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
+@pytest.mark.copyright
+@pytest.mark.linter
+def test_copyright():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found errors'
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/test/test_flake8.py b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/test/test_flake8.py
new file mode 100644
index 0000000000000000000000000000000000000000..27ee1078ff077cc3a0fec75b7d023101a68164d1
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/test/test_flake8.py
@@ -0,0 +1,25 @@
+# Copyright 2017 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_flake8.main import main_with_errors
+import pytest
+
+
+@pytest.mark.flake8
+@pytest.mark.linter
+def test_flake8():
+    rc, errors = main_with_errors(argv=[])
+    assert rc == 0, \
+        'Found %d code style errors / warnings:\n' % len(errors) + \
+        '\n'.join(errors)
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/test/test_pep257.py b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/test/test_pep257.py
new file mode 100644
index 0000000000000000000000000000000000000000..b234a3840f4c5bd38f043638c8622b8f240e1185
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/line_follower_pkg/test/test_pep257.py
@@ -0,0 +1,23 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_pep257.main import main
+import pytest
+
+
+@pytest.mark.linter
+@pytest.mark.pep257
+def test_pep257():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found code style errors / warnings'
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/package.xml b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/package.xml
new file mode 100644
index 0000000000000000000000000000000000000000..f09c1359b3def53e576397710d621e114721a6e7
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/package.xml
@@ -0,0 +1,18 @@
+<?xml version="1.0"?>
+<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
+<package format="3">
+  <name>pico_reader_pkg</name>
+  <version>0.0.0</version>
+  <description>TODO: Package description</description>
+  <maintainer email="turtlebot@todo.todo">turtlebot</maintainer>
+  <license>TODO: License declaration</license>
+
+  <test_depend>ament_copyright</test_depend>
+  <test_depend>ament_flake8</test_depend>
+  <test_depend>ament_pep257</test_depend>
+  <test_depend>python3-pytest</test_depend>
+
+  <export>
+    <build_type>ament_python</build_type>
+  </export>
+</package>
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/pico_reader_pkg/__init__.py b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/pico_reader_pkg/__init__.py
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/pico_reader_pkg/pico_reader_node.py b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/pico_reader_pkg/pico_reader_node.py
new file mode 100644
index 0000000000000000000000000000000000000000..4e155b53a026c10d1b5095399aad2cbf774a6ada
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/pico_reader_pkg/pico_reader_node.py
@@ -0,0 +1,72 @@
+import rclpy
+from rclpy.node import Node
+from std_msgs.msg import String
+import serial
+
+class PicoReaderNode(Node):
+    def __init__(self):
+        super().__init__('pico_reader_node')
+        self.declare_parameter('serial_port', '/dev/ttyACM0')  # Neue serielle Schnittstelle
+        self.declare_parameter('baud_rate', 9600)  # Neue Baudrate
+        
+        serial_port = self.get_parameter('serial_port').get_parameter_value().string_value
+        baud_rate = self.get_parameter('baud_rate').get_parameter_value().integer_value
+        
+        try:
+            self.serial_conn = serial.Serial(serial_port, baud_rate, timeout=1)
+            self.get_logger().info(f'Connected to serial port: {serial_port}')
+        except Exception as e:
+            self.get_logger().error(f'Failed to connect to serial port: {e}')
+            rclpy.shutdown()
+
+        self.line_sensor_publisher = self.create_publisher(String, 'line_sensor_data', 1)
+        self.front_collision_publisher = self.create_publisher(String, 'front_collision_data', 1)
+        
+        self.timer = self.create_timer(0.05, self.read_from_pico)  # 20 Hz Update-Rate (0.05 Sekunden)
+
+    def read_from_pico(self):
+        try:
+            if self.serial_conn.in_waiting > 0:
+                data = self.serial_conn.readline().decode('utf-8').strip()
+                self.process_sensor_data(data)
+        except Exception as e:
+            self.get_logger().error(f'Error reading from serial: {e}')
+
+    def process_sensor_data(self, data):
+        try:
+            # Erwartetes Datenformat: "0,1,1,0,1,25.6"
+            parts = data.split(',')
+            if len(parts) == 6:
+                # Liniensensoren
+                line_sensor_values = parts[:5]
+                line_sensor_msg = String()
+                line_sensor_msg.data = ','.join(line_sensor_values)
+                self.line_sensor_publisher.publish(line_sensor_msg)
+
+                # HC-SR04 (Entfernung)
+                distance_value = parts[5]
+                collision_msg = String()
+                collision_msg.data = distance_value
+                self.front_collision_publisher.publish(collision_msg)
+
+                self.get_logger().info(f'Published line sensor data: {line_sensor_msg.data}')
+                self.get_logger().info(f'Published front collision data: {collision_msg.data}')
+            else:
+                self.get_logger().warn(f'Unexpected data format: {data}')
+        except Exception as e:
+            self.get_logger().error(f'Error processing sensor data: {e}')
+
+def main(args=None):
+    rclpy.init(args=args)
+    node = PicoReaderNode()
+    try:
+        rclpy.spin(node)
+    except KeyboardInterrupt:
+        node.get_logger().info('Node stopped by user')
+    finally:
+        if node.serial_conn:
+            node.serial_conn.close()
+        rclpy.shutdown()
+
+if __name__ == '__main__':
+    main()
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/resource/pico_reader_pkg b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/resource/pico_reader_pkg
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/setup.cfg b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/setup.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..3609d04a475e25ff64b5f0f2098d834ff658a4b0
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/setup.cfg
@@ -0,0 +1,4 @@
+[develop]
+script_dir=$base/lib/pico_reader_pkg
+[install]
+install_scripts=$base/lib/pico_reader_pkg
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/setup.py b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/setup.py
new file mode 100644
index 0000000000000000000000000000000000000000..3d58152e10050bb5c6b8eb9e3b919a5ffc19037d
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/setup.py
@@ -0,0 +1,27 @@
+from setuptools import find_packages, setup
+
+package_name = 'pico_reader_pkg'
+
+setup(
+    name=package_name,
+    version='0.0.0',
+    packages=find_packages(exclude=['test']),
+    data_files=[
+        ('share/ament_index/resource_index/packages',
+         ['resource/' + package_name]),
+        ('share/' + package_name, ['package.xml']),
+    ],
+    install_requires=['setuptools'],
+    zip_safe=True,
+    maintainer='turtlebot',
+    maintainer_email='turtlebot@todo.todo',
+    description='ROS 2 Package for reading data from a Raspberry Pi Pico via USB',
+    license='Apache License 2.0',
+    tests_require=['pytest'],
+    entry_points={
+        'console_scripts': [
+            'pico_reader_node = pico_reader_pkg.pico_reader_node:main',
+        ],
+    },
+)
+
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/test/test_copyright.py b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/test/test_copyright.py
new file mode 100644
index 0000000000000000000000000000000000000000..97a39196e84db97954341162a6d2e7f771d938c0
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/test/test_copyright.py
@@ -0,0 +1,25 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_copyright.main import main
+import pytest
+
+
+# Remove the `skip` decorator once the source file(s) have a copyright header
+@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
+@pytest.mark.copyright
+@pytest.mark.linter
+def test_copyright():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found errors'
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/test/test_flake8.py b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/test/test_flake8.py
new file mode 100644
index 0000000000000000000000000000000000000000..27ee1078ff077cc3a0fec75b7d023101a68164d1
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/test/test_flake8.py
@@ -0,0 +1,25 @@
+# Copyright 2017 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_flake8.main import main_with_errors
+import pytest
+
+
+@pytest.mark.flake8
+@pytest.mark.linter
+def test_flake8():
+    rc, errors = main_with_errors(argv=[])
+    assert rc == 0, \
+        'Found %d code style errors / warnings:\n' % len(errors) + \
+        '\n'.join(errors)
diff --git a/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/test/test_pep257.py b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/test/test_pep257.py
new file mode 100644
index 0000000000000000000000000000000000000000..b234a3840f4c5bd38f043638c8622b8f240e1185
--- /dev/null
+++ b/Code/ROS_Nodes_fuer_5_Sensoren/pico_reader_pkg/test/test_pep257.py
@@ -0,0 +1,23 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+from ament_pep257.main import main
+import pytest
+
+
+@pytest.mark.linter
+@pytest.mark.pep257
+def test_pep257():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found code style errors / warnings'
diff --git a/Code/RPi4(Python)/TCRT5000.py b/Code/RPi4(Python)/TCRT5000.py
new file mode 100644
index 0000000000000000000000000000000000000000..bc47f347a5ab1c7d5c6ba7fe9ea01cc297afc040
--- /dev/null
+++ b/Code/RPi4(Python)/TCRT5000.py
@@ -0,0 +1,41 @@
+# Auslesen zweier TCRT5000 Liniensensoren auf einem Raspberry Pi 4 unter Ubuntu 22.04
+
+import RPi.GPIO as GPIO
+import time
+
+# Pin-Nummer des Linken Sensors (OUT-Pin ist mit GPIO17 verbunden)
+LEFT_PIN = 17
+# Pin-Nummer des Rechten Sensors (OUT-Pin ist mit GPIO26 verbunden)
+RIGHT_PIN = 26
+
+# GPIO-Modus einstellen
+GPIO.setmode(GPIO.BCM)
+GPIO.setup(LEFT_PIN, GPIO.IN)
+GPIO.setup(RIGHT_PIN, GPIO.IN)
+
+
+try:
+    while True:
+        # Sensor-Ausgang lesen
+        left_value = GPIO.input(LEFT_PIN)
+        right_value = GPIO.input(RIGHT_PIN)
+
+        if left_value == 1:
+            print("LINKS: 1 -> schwarz")
+        else:
+            print("LINKS: 0 -> hell")
+
+        if right_value == 1:
+            print("RECHTS: 1 -> schwarz")
+        else:
+            print("RECHTS: 0 -> hell")
+
+        # Verzögerung für bessere Lesbarkeit
+        time.sleep(0.3)
+
+except KeyboardInterrupt:
+    print("Programm beendet")
+
+finally:
+    GPIO.cleanup()
+
diff --git a/Code/RPi4(Python)/hc_sr04.py b/Code/RPi4(Python)/hc_sr04.py
new file mode 100644
index 0000000000000000000000000000000000000000..f22ea8b74ddcd5b6c69aac3713c383fcc33deb42
--- /dev/null
+++ b/Code/RPi4(Python)/hc_sr04.py
@@ -0,0 +1,49 @@
+# Den HC-SR04 mit einem Raspberry Pi 4 unter Ubuntu auslesen
+
+import RPi.GPIO as GPIO
+import time
+
+# Pin-Definitionen (Passe sie an dein Setup an)
+TRIG_PIN = 2  # Pin für TRIG
+ECHO_PIN = 3  # Pin für ECHO
+
+# GPIO konfigurieren
+GPIO.setmode(GPIO.BCM)
+GPIO.setup(TRIG_PIN, GPIO.OUT)
+GPIO.setup(ECHO_PIN, GPIO.IN)
+
+def get_distance():
+    """
+    Misst die Entfernung mithilfe des HC-SR04 Sensors.
+    Gibt die Entfernung in Zentimetern zurück.
+    """
+    # Trigger-Puls erzeugen
+    GPIO.output(TRIG_PIN, True)
+    time.sleep(0.00001)  # 10 µs Pulse
+    GPIO.output(TRIG_PIN, False)
+
+    # Warte auf den Start des ECHO-Signals
+    while GPIO.input(ECHO_PIN) == 0:
+        start_time = time.time()
+
+    # Warte auf das Ende des ECHO-Signals
+    while GPIO.input(ECHO_PIN) == 1:
+        end_time = time.time()
+
+    # Zeitdifferenz berechnen
+    duration = end_time - start_time
+
+    # Entfernung berechnen (Schallgeschwindigkeit = 34300 cm/s)
+    distance = (duration * 34300) / 2  # Hin- und Rückweg beachten
+    return distance
+
+try:
+    while True:
+        dist = get_distance()
+        print(f"Gemessene Entfernung: {dist:.2f} cm")
+        time.sleep(1)  # Wartezeit zwischen Messungen
+
+except KeyboardInterrupt:
+    print("Messung beendet")
+    GPIO.cleanup()  # GPIO sauber freigeben
+
diff --git a/Code/RPi4(Python)/led.py b/Code/RPi4(Python)/led.py
new file mode 100644
index 0000000000000000000000000000000000000000..5dcfa4f20a4b649582c05caa5c47179a434622f8
--- /dev/null
+++ b/Code/RPi4(Python)/led.py
@@ -0,0 +1,22 @@
+import RPi.GPIO as GPIO
+import time
+
+# GPIO-Modus einstellen (BCM oder BOARD)
+
+GPIO.setmode(GPIO.BCM)
+
+# GPIO-Pin definieren
+LED_PIN = 17
+
+# Pin als Ausgang festlegen
+GPIO.setup(LED_PIN, GPIO.OUT)
+
+# LED blinken lassen
+try:
+    while True:
+        GPIO.output(LED_PIN, GPIO.HIGH)  # LED einschalten
+        time.sleep(1)                   # 1 Sekunde warten
+        GPIO.output(LED_PIN, GPIO.LOW)  # LED ausschalten
+        time.sleep(1)
+except KeyboardInterrupt:
+    GPIO.cleanup()  # GPIO-Pins zurücksetzen
\ No newline at end of file
diff --git a/Code/RPi4(Python)/line_follower_node.py b/Code/RPi4(Python)/line_follower_node.py
new file mode 100644
index 0000000000000000000000000000000000000000..a753d3fdb708a29f0d2a6595547f2d741fecdb72
--- /dev/null
+++ b/Code/RPi4(Python)/line_follower_node.py
@@ -0,0 +1,68 @@
+import rclpy
+from rclpy.node import Node
+from geometry_msgs.msg import Twist
+from std_msgs.msg import String
+
+class LineFollowerNode(Node):
+    def __init__(self):
+        super().__init__('line_follower')
+        
+        # Abonnieren der Pico-Daten
+        self.sensor_subscription = self.create_subscription(
+            String,
+            'pico_data',  # Topic für die Pico-Daten
+            self.sensor_callback,
+            10)
+        
+        # Publisher für Bewegungsbefehle
+        self.cmd_publisher = self.create_publisher(Twist, '/cmd_vel', 10)
+
+        # Initialisierung der Steuerungsvariablen
+        self.left_sensor = 0.0
+        self.right_sensor = 0.0
+
+    def sensor_callback(self, msg):
+        try:
+            # Verarbeiten der Sensordaten aus der Nachricht
+            data = msg.data.split(',')  # Annahme: Daten sind als "Wert1,Wert2" formatiert
+            self.left_sensor = float(data[0])  # Linker Sensorwert
+            self.right_sensor = float(data[1])  # Rechter Sensorwert
+            self.get_logger().info(f"Left: {self.left_sensor}, Right: {self.right_sensor}")
+            
+            # Linie folgen
+            self.follow_line()
+        except (ValueError, IndexError) as e:
+            self.get_logger().error(f"Fehler beim Verarbeiten der Sensordaten: {e}")
+
+    def follow_line(self):
+        twist_msg = Twist()
+
+        if self.left_sensor > self.right_sensor:
+            # Drehe nach links
+            twist_msg.linear.x = 0.05
+            twist_msg.angular.z = -0.2
+        elif self.right_sensor > self.left_sensor:
+            # Drehe nach rechts
+            twist_msg.linear.x = 0.05
+            twist_msg.angular.z = +0.2
+        else:
+            # Geradeaus fahren
+            twist_msg.linear.x = 0.1
+            twist_msg.angular.z = 0.0
+
+        # Bewegungsbefehle senden
+        self.cmd_publisher.publish(twist_msg)
+
+def main(args=None):
+    rclpy.init(args=args)
+    node = LineFollowerNode()
+    try:
+        rclpy.spin(node)
+    except KeyboardInterrupt:
+        pass
+    finally:
+        node.destroy_node()
+        rclpy.shutdown()
+
+if __name__ == '__main__':
+    main()
diff --git a/Code/RPi4(Python)/read_pico.py b/Code/RPi4(Python)/read_pico.py
new file mode 100644
index 0000000000000000000000000000000000000000..8e36a7af3dc603ff4a0932142ec9f2e8d071342d
--- /dev/null
+++ b/Code/RPi4(Python)/read_pico.py
@@ -0,0 +1,33 @@
+# Liest die Signale eines über USB angeschlossenen
+# Raspberry Pi Picos aus und gibt diese aus.
+# Der Pico sollte sich auf einem Raspberry Pi 
+# mit ls /dev/tty* finden lassen.
+
+import serial
+import time
+
+# Seriellen Port und Baudrate definieren
+SERIAL_PORT = '/dev/ttyACM0'  # Passe dies an, falls nötig
+BAUD_RATE = 9600
+
+try:
+    # Verbindung zum Pico öffnen
+    pico_serial = serial.Serial(SERIAL_PORT, BAUD_RATE, timeout=1)
+    print(f"Verbindung zu {SERIAL_PORT} hergestellt")
+
+    while True:
+        # Daten vom Pico lesen
+        if pico_serial.in_waiting > 0:
+            data = pico_serial.readline().decode('utf-8').strip()
+            print(f"Empfangen: {data}")
+
+except serial.SerialException as e:
+    print(f"Fehler bei der seriellen Verbindung: {e}")
+
+except KeyboardInterrupt:
+    print("Programm beendet")
+
+finally:
+    if 'pico_serial' in locals() and pico_serial.is_open:
+        pico_serial.close()
+        print("Serielle Verbindung geschlossen")
diff --git a/Code/check_battery.sh b/Code/check_battery.sh
new file mode 100644
index 0000000000000000000000000000000000000000..797454b27e3c39bce7235ebb72489c7cefcda39c
--- /dev/null
+++ b/Code/check_battery.sh
@@ -0,0 +1,20 @@
+# Dieses Skript soll auf einem Turtlebot die Batterieladung ausgeben 
+
+
+#!/bin/bash
+
+# ROS 2 Umgebung sourcen (Pfad anpassen)
+source /opt/ros/<ros_distribution>/setup.bash
+
+# Abonniere das /battery_state Topic und verarbeite die Batteriedaten
+echo "Starte Batteriestatus-Ãœberwachung des TurtleBot..."
+ros2 topic echo /battery_state | while read -r line; do
+    if [[ $line == *"percentage:"* ]]; then
+        # Extrahiere den Prozentsatz
+        percentage=$(echo "$line" | awk '{print $2}')
+        # Multipliziere mit 100, um den Wert in Prozent zu erhalten
+        percentage_in_percent=$(awk "BEGIN {print $percentage * 100}")
+        # Ausgabe der Batterieladung in derselben Zeile
+        echo -ne "Batterieladung: ${percentage_in_percent}%\r"
+    fi
+done
diff --git a/Code/turtlebot.zip b/Code/turtlebot.zip
new file mode 100644
index 0000000000000000000000000000000000000000..c6dd8417cad8ec707cdf5461d38e066b81db43bb
Binary files /dev/null and b/Code/turtlebot.zip differ
diff --git a/Dokumentation/Inbetriebnahme_Turtlebot_4.md b/Dokumentation/Inbetriebnahme_Turtlebot_4.md
new file mode 100644
index 0000000000000000000000000000000000000000..6c14515df18cc8a14299aa81ff6e0a7457a2acf2
--- /dev/null
+++ b/Dokumentation/Inbetriebnahme_Turtlebot_4.md
@@ -0,0 +1,76 @@
+1. [Inbetriebnahme Turtlebot 4](Dokumentation/Inbetriebnahme_Turtlebot_4.md)
+2. [ROS Basics](Dokumentation/ROS2_Basics.md)
+3. [Sensoren](Dokumentation/Sensoren.md)
+4. [Navigation](Dokumentation/Navigation.md)
+
+---
+# Inbetriebnahme Turtlebot 4
+
+### Den Raspberry Pi aufsetzten
+
+Hierzu sollte man den [Raspberry Pi Imager](https://www.raspberrypi.com/software/) oder Ähnliches installiert haben.
+###### Vorgefertigtes Image für einen Raspberry Pi 4 installieren *(Empfohlen)*
+- mit **Ubuntu 22.04**
+- auf dem **ROS2 Humble** läuft
+- mit welchem ein **Turtlebot 4** voll funktionsfähig ist
+- mit Benutzernamen `turtlebot` und Passwort `turtlebot4`
+- und auf welchem SSH aktiviert ist
+
+Wir haben manuell einmal die Umgebung für einen Turtlebot 4 aufgesetzt und haben davon ein Image erstellt. Dieses findet sich **[hier](../Code/turtlebot.zip)** und kann mit dem Raspberry Pi Imager auf eine SD Karte kopiert werden.
+
+Alternativ werden auf der ROS Seite auch fertige Images zum [Download](http://download.ros.org/downloads/turtlebot4/) angeboten, dieses hat bei uns aber nicht funktioniert. Die Anmeldedaten sind hier `ubuntu` und `turtlebot4`.
+
+###### Manuell selbst aufsetzen
+- Im Raspberrry Pi Imager als Betriebssystem `Ubuntu Server 22.04.05 LTS (64-bit)` unter `Other general-purpose OS` -> `Ubuntu` auswählen
+- Es bietet sich an im nächsten Schritt direkt SSH zu aktiveren um direkt in einen headless Betrieb (also ohne Monitor, Tastatur etc.) zu ermöglichen. In diesem Schritt lässt sich auch gleich das WLAN einrichten.
+  
+  <img src="/Bilder/pi_imager.png" alt="Imager" width="800">
+
+  <img src="/Bilder/Anpassungen.png" alt="Anpassungen" width="800">
+   
+  <img src="/Bilder/SSH.png" alt="SSH" width="400">
+ 
+  *Screenshots aus dem [Raspberry Pi Imager](https://www.raspberrypi.com/software/)*
+- Den Raspberry Pi in Betrieb nehmen und aktualisieren mit `sudo apt update && sudo apt upgrade -y`
+- Jetzt bieten sich zwei Möglichkeiten
+	- **Option A: Setup Skript *(Empfohlen)***
+		- Wie [hier](https://github.com/turtlebot/turtlebot4_setup/tree/humble) beschrieben Skript runterladen und ausführen mit:
+	
+		  ``` wget -qO - https://raw.githubusercontent.com/turtlebot/turtlebot4_setup/humble/scripts/turtlebot4_setup.sh | bash ```
+	- **Option B: Software manuell installieren**
+		- [ROS2 installieren](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debs.html)
+		- [Turtlebot 4 Pakete installieren](https://turtlebot.github.io/turtlebot4-user-manual/setup/basic.html)
+
+
+###### WLAN Setup
+- Standardmäßig befindet sich der Turtlebot im Access-Point Mode. Das heißt Der Turtlebot eröffnet sein eigenes WLAN mit dem Namen `Turtlebot4` und dem Passwort `Turtlebot4`.
+- Mit `turtlebot4-setup` das WLAN Setup ändern. Es lassen sich WLAN Name und Passwort des vom Turtlebot eröffneten Netzwerks ändern aber auch in den Client Mode wechseln mit welchem sich der Turtlebot in ein beliebiges anderes WLAN einbinden lässt. 
+  
+  <img src="/Bilder/turtlebot-setup.png" alt="turtlebot-setup" width="800">
+  
+  <img src="/Bilder/wifi-setup.png" alt="wifi-setup" width="800">
+  
+- Erfahrungsgemäß braucht der Turtlebot nach ändern dieser Einstellungen einen Neustart mit einer gewissen Pause vor dem erneuten Hochfahren um die Änderungen erfolgreich anzuwenden.
+- Ist der Turtlebot durch das Ändern der Einstellungen nicht mehr erreichbar bietet es sich an den Pi per LAN Kabel an einen Router zu hängen, sich per SSH mit dem Turtlebot zu verbinden und erneut mit `turtlebot4-setup` den Fehler zu begradigen.
+- Sollte man die IP des Pis nicht kennen können Netzwerkscanner helfen mit denen alle Geräte in einem Netzwerk samt IP aufgelistet werden. Unter Windows wäre das zum Beispiel [Advanced IP Scanner](https://www.heise.de/download/product/advanced-ip-scanner-19718) oder unter Android [Wifiman](https://play.google.com/store/apps/details?id=com.ubnt.usurvey&hl=de).
+- Hilfreich war für uns auch das SFTP Protokoll und [Filezilla](https://filezilla-project.org/). Mit SFPT lassen sich Daten über SSH transportieren, die Anmeldung funktioniert wie bei SSH.
+  
+  <img src="/Bilder/filezilla.png" alt="Filezilla" width="800">
+  
+  *Screenshot aus [Filezilla](https://filezilla-project.org/)*
+###### Troubleshooting - falls Probleme auftreten
+- Sicherstellen dass die Firmware der Create 3 Basis auch der ROS Version des Turtlebots entspricht, in unserem Fall ROS 2 Humble. Ist das nicht der Fall kann der Pi Probleme haben mit der Create 3 Basis zu kommunizieren, entsprechend fehlen dann bestimmte ROS Nodes und der Turtlebot kann beispielsweise nicht fahren. Das Ganze lässt sich auf dem Webserver des Create 3 überprüfen. Hierzu die IP des Pis mit dem Port 8080 in den Browser eingeben (in unserem Fall zB. `192.168.178.155:8080`).
+  
+  <img src="/Bilder/firmware_checken.png" alt="firmware checken" width="800">
+###### Wichtige/Hilfreiche Pakete
+*(erst die Paketlisten aktualisieren mit `sudo apt update`)*
+
+`sudo apt install python3 python3-pip mc tree net-tools`
+- `python3` ist wichtig
+- `python3-pip` pip ist der Paketmanager für Python 3, mit dem sich Python-Bibliotheken aus dem Python Package Index (PyPI) installieren, aktualisieren und verwalten lassen
+- `mc` Midnightcommander, praktischer textbasierter Dateimanager, bringt den eingebauten Editor `mcedit` mit sich
+- `tree` zeigt die Verzeichnisstruktur eines Ordners in einer hierarchischen Baumdarstellung im Terminal an
+- `net-tools` mit dem Befehl `ifconfig` lässt sich beispielsweise die eigene IP auslesen
+
+###### Eigene Sicherheitskopien erstellen
+Es kann sehr wichtig sein Sicherheitskopien der SD Karte vom Raspberry Pi zu erstellen. Unter Windows haben wir dafür [Win32 Disk Imager](https://win32diskimager.org/) verwendet.
\ No newline at end of file
diff --git a/Dokumentation/Navigation.md b/Dokumentation/Navigation.md
new file mode 100644
index 0000000000000000000000000000000000000000..9a9a6cb5b2eca0df7b0dab06a7b6053cbd45dd49
--- /dev/null
+++ b/Dokumentation/Navigation.md
@@ -0,0 +1,122 @@
+1. [Inbetriebnahme Turtlebot 4](Dokumentation/Inbetriebnahme_Turtlebot_4.md)
+2. [ROS Basics](Dokumentation/ROS2_Basics.md)
+3. [Sensoren](Dokumentation/Sensoren.md)
+4. [Navigation](Dokumentation/Navigation.md)
+
+---
+
+# Erstes Szenario: Einer Linie folgen mit zwei Liniensensoren
+
+Dieses Navigationsszenario ermöglicht einem TurtleBot, einer Linie auf dem Boden zu folgen. Die Umsetzung erfolgt durch eine Kombination von Hardware (TurtleBot 4, Raspberry Pi Pico, und TCRT5000-Liniensensoren) und einer Softwareintegration unter Verwendung von ROS 2 Humble. Nachfolgend wird der Prozess detailliert beschrieben:
+
+###### Hardwareaufbau
+
+1. **TCRT5000 Liniensensoren**:
+	- Zwei TCRT5000-Sensoren sind für die Erkennung der Linie auf dem Boden zuständig. Sie messen die Helligkeit des Bodens und erkennen den Kontrast zwischen der Linie und der Umgebung.
+    - Diese Sensoren sind physisch ausgelagert und an einen **Raspberry Pi Pico** angeschlossen.
+3. **Raspberry Pi Pico**:
+    - Der Pico fungiert als Mittler, der die Sensordaten von den TCRT5000-Sensoren aufnimmt.
+    - Die Verarbeitung der Daten erfolgt in Echtzeit, und die relevanten Informationen werden über eine **serielle USB-Schnittstelle** an den Hauptrechner des TurtleBot weitergeleitet.
+3. **Raspberry Pi auf dem TurtleBot**:
+    - Der Hauptrechner des TurtleBot empfängt die Sensordaten über die USB-Verbindung und integriert diese in das Robot Operating System (ROS 2 Humble).
+
+###### Software-Integration
+
+Die Software wird durch zwei ROS-Pakete organisiert:
+
+1. **`pico_reader_node`**:
+    - Dieser Node ist für die Kommunikation mit dem Raspberry Pi Pico zuständig.
+    - Er liest die von den TCRT5000-Sensoren gelieferten Sensordaten über die serielle Schnittstelle und veröffentlicht diese als ROS-Topic, sodass andere ROS-Nodes darauf zugreifen können.
+2. **`line_follower_node`**:
+    - Dieser Node empfängt die Sensordaten, die vom `pico_reader_node` bereitgestellt werden.
+    - Basierend auf den Daten entscheidet er, wie der TurtleBot gesteuert werden soll, um der Linie zu folgen.
+    - Typischerweise werden folgende Bewegungslogiken implementiert:
+        - **Beide Sensoren erkennen die Linie**: Der TurtleBot bewegt sich geradeaus.
+        - **Nur der linke Sensor erkennt die Linie**: Der TurtleBot dreht nach links.
+        - **Nur der rechte Sensor erkennt die Linie**: Der TurtleBot dreht nach rechts.
+        - **Kein Sensor erkennt die Linie**: Der TurtleBot stoppt oder sucht nach der Linie.
+
+###### ROS-Integration
+- Die Sensordaten werden als ROS-Topics veröffentlicht, was eine modulare und flexible Architektur ermöglicht.
+- Der `line_follower_node` nutzt diese Topics, um Echtzeit-Befehle an die Bewegungssteuerung des TurtleBots zu senden.
+
+###### Vorteile dieses Setups
+1. **Modularität**:
+    - Durch die Verwendung von ROS können die Nodes unabhängig voneinander entwickelt, getestet und erweitert werden.
+2. **Effiziente Verarbeitung**:
+    - Die Auslagerung der Sensordatenverarbeitung auf den Raspberry Pi Pico entlastet den Hauptrechner des TurtleBots.
+3. **Einfache Erweiterbarkeit**:
+    - Zusätzliche Funktionen wie Hinderniserkennung oder erweiterte Navigationslogik können durch weitere Nodes hinzugefügt werden.
+
+Dieses Szenario stellt eine einfache und dennoch robuste Lösung für die Linienverfolgung dar und zeigt, wie eine durchdachte Hardware- und Softwareintegration die Autonomie mobiler Roboter verbessern kann.
+
+
+#### Erstellen des Workspaces und Pakets
+- Die beiden Pakete `line_follower_pkg` und `pico_reader_pkg` finden sich [hier](../Code/ROS_Nodes_fuer_2_Sensoren).
+- Diese in den `src`-Ordner des eigenen Workspaces kopieren
+- Anschließen bauen und sourcen
+#### Ausführen
+- In einem Fenster mit `ros2 run pico_reader_pkg pico_reader_node` die Sensoren auslesen
+- In einem anderen Fenster mit `ros2 run line_follower_pkg line_follower_node` die Navigation starten
+
+
+![Einer Linie folgen mit dem Turtlebot und zwei Liniensensoren](../Bilder/linie_folgen_2S.mp4)
+
+
+# Zweites Szenario: Einer Linie folgen mit fünf Liniensensoren
+
+Wir bauen auf dem ersten Szenario auf, erweitern es auf insgesamt fünf Liniensensoren, einem Ultraschall-Distanzsensor und verpacken alles in einer entsprechenden Einhausung.
+
+### Einhausung Liniensensoren + Ultraschall
+
+<img src="/Bilder/frontal.jpg" alt="Sensoreinhausung" width="600">
+
+Ziel ist es die fünf Liniensensoren und einen Ultraschallsensor mit einem Raspberry Pi Pico auszulesen und über diesen die Messwerte per serieller USB Schnittstelle an den Raspberry Pi 4 weiterzugeben. Hierfür braucht es ein Gehäuse in welchem
+- 1x HC-SR04,
+- 5x TCRT5000
+- und der Raspberry Pi Pico
+
+Platz finden. Dieses wird vorne an den Turtlebot angebracht. Der USB Port des Picos muss zugänglich bleiben.
+
+**Die CAD Dateien finden sich [hier](/Komponenten/).**
+![Explosionsdarstellung](/Bilder/explosionsdarstellung.mp4)
+
+### **Komponenten und Funktionen**
+
+<img src="/Bilder/Sensoren.jpg" alt="Sensoren" width="600">
+
+##### **1. Liniensensoren (TCRT5000)**
+
+- Der Vorbau beherbergt **fünf TCRT5000-Liniensensoren**, die gleichmäßig im unteren Bereich positioniert sind.
+- Die Sensoren sind nach unten gerichtet und messen die Reflexion von Infrarotlicht auf der Bodenoberfläche. Dies ermöglicht es dem TurtleBot, Bodenmarkierungen oder Linien präzise zu folgen.
+- Die Sensoren wurden in einer leicht gebogenen Anordnung platziert, um eine optimale Abdeckung zu gewährleisten, auch bei Kurvenfahrten.
+
+##### **2. Ultraschallsensor (HC-SR04)**
+
+- Im vorderen Bereich des Vorbaus ist ein **HC-SR04-Ultraschallsensor** integriert. Dieser Sensor misst Entfernungen zu Objekten und erkennt Hindernisse in Fahrtrichtung.
+- Die offene Platzierung des Sensors ermöglicht eine ungestörte Messung im Nahbereich und schützt ihn gleichzeitig vor physischen Einwirkungen.
+
+##### **3. Mikrocontroller (Raspberry Pi Pico)**
+
+- Ein **Raspberry Pi Pico** ist im Inneren des Gehäuses montiert und dient als zentrale Steuerungseinheit für die angeschlossenen Sensoren.
+- Der Pico verarbeitet die Signale der Sensoren und sendet die Daten an die Hauptsteuerung des TurtleBot, dem Raspberry Pi 4, weiter.
+
+
+### Systemstruktur
+
+<img src="/Bilder/systemstruktur.jpg" alt="Systemstruktur" width="800">
+
+### ROS2 Code
+
+###### ROS2-Architektur
+<img src="/Bilder/ros_architektur.jpg" alt="ROS2 Architektur" width="800">
+
+###### Algorithmus
+<img src="/Bilder/algorithmus.jpg" alt="Algorithmus" width="800">
+
+Die beiden ROS2 Nodes finden sich [hier](/Code/ROS_Nodes_fuer_5_Sensoren). Die Benutzung funktioniert analog zum ersten Beispiel.
+
+### Video
+
+
+![Turtlebot fährt eine Acht](/Bilder/acht.mp4)
\ No newline at end of file
diff --git a/Dokumentation/README.md b/Dokumentation/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..0c97677f47c17e3c1c1c5cb4a7468f9dc1797e60
--- /dev/null
+++ b/Dokumentation/README.md
@@ -0,0 +1,4 @@
+1. [Inbetriebnahme Turtlebot 4](Dokumentation/Inbetriebnahme_Turtlebot_4.md)
+2. [ROS Basics](Dokumentation/ROS2_Basics.md)
+3. [Sensoren](Dokumentation/Sensoren.md)
+4. [Navigation](Dokumentation/Navigation.md)
\ No newline at end of file
diff --git a/Dokumentation/ROS2_Basics.md b/Dokumentation/ROS2_Basics.md
new file mode 100644
index 0000000000000000000000000000000000000000..055d9d83d4581246ba02611345b0a481d2a7a032
--- /dev/null
+++ b/Dokumentation/ROS2_Basics.md
@@ -0,0 +1,47 @@
+1. [Inbetriebnahme Turtlebot 4](Dokumentation/Inbetriebnahme_Turtlebot_4.md)
+2. [ROS Basics](Dokumentation/ROS2_Basics.md)
+3. [Sensoren](Dokumentation/Sensoren.md)
+4. [Navigation](Dokumentation/Navigation.md)
+
+---
+# ROS2 Basics
+
+***ROS (Robot Operating System)** ist ein Framework zur Entwicklung von Software für Roboter. Es bietet eine Reihe von Tools, Bibliotheken und Konventionen, die Entwicklern dabei helfen, komplexe und robuste Roboteranwendungen zu erstellen. Obwohl der Name "Operating System" impliziert, dass es sich um ein Betriebssystem handelt, ist ROS tatsächlich eine Middleware, die auf einem bestehenden Betriebssystem läuft (normalerweise Linux, wie Ubuntu).
+
+Wir verwenden die Version ROS2 Humble*
+
+#### Häufig genutzte Befehle
+- Liste aller Nodes anzeigen lassen: `ros2 node list`
+- Liste aller Topics anzeigen lassen: `ros2 topic list`
+- Topic-Details anzeigen: `ros2 topic info /hazard_detection`
+- Message-Typ eines Topics anzeigen: `ros2 topic type /hazard_detection`
+- Nachrichten eines Topics auslesen: `ros2 topic echo /topic`
+- Checken welche Workspaces geladen sind: `ros2 pkg list`
+- Das Shell-Skript [check_battery.sh](../Code/check_battery.sh) greift über ROS den Batterieladestand ab und zeigt diesen an
+
+#### Den Turtlebot steuern
+- Mit der Tastatur den Turtlebot fernsteuern: `ros2 run teleop_twist_keyboard teleop_twist_keyboard`
+- Den Turtlebot laden schicken: `ros2 action send_goal /dock irobot_create_msgs/action/Dock "{}"`
+- Das Ding abdocken lassen: `ros2 action send_goal /undock irobot_create_msgs/action/Undock "{}"`
+
+#### Erstellen eines Workspaces und Pakets
+- Ordner erstellen,  der Name `ros2_ws` kann dabei beliebig ersetzt werden: ```mkdir -p ~/ros2_ws/src```
+#### Erstellen eines Pakets
+- In den `src`  Ordner des Workspaces wechseln: ```cd ~/ros2_ws/src```
+- Das Paket erstellen, dabei auch die Abhängigkeiten angeben: ```ros2 pkg create paket_name --build-type ament_python --dependencies abhängigkeit1 abnhängigkeit2```
+#### Erstellen einer Node
+- In dem gerade erstellten Paket findet sich ein Ordner mit dem selben Namen des Pakets. Hier werden die Nodes gespeichert.
+  So kann beispielsweise die Ordnerstruktur eines Pakets aussehen:
+  
+  ![packet](../Bilder/paket.png)
+- In der `setup.py` ist es außerdem wichtig unter `entry_ponts` die Nodes anzugeben.
+  Hier ein Beispiel:
+  ![entrypoint](../Bilder/entrypoint.png) 
+#### Das Workspace bauen
+- Zurück ins Stammverzeichnis des Workspaces wechseln: ```cd ~/turtlebot4_ws```
+- Den Workspace bauen: ```colcon build```
+- Den Workspace für ROS auffindbar machen: ```source install/setup.bash``` **Das muss für jede Terminal Instanz separat gemacht werden.**
+
+#### Eine Node ausführen
+- Allgemein: ```ros2 run paketname nodename```
+- Konkretes Beispiel: ```ros2 run line_follower_pkg line_follower_node```
\ No newline at end of file
diff --git a/Dokumentation/Sensoren.md b/Dokumentation/Sensoren.md
new file mode 100644
index 0000000000000000000000000000000000000000..1cb31a79e790d9fc0b38a5f9252bdfeed3b0aee9
--- /dev/null
+++ b/Dokumentation/Sensoren.md
@@ -0,0 +1,235 @@
+1. [Inbetriebnahme Turtlebot 4](Dokumentation/Inbetriebnahme_Turtlebot_4.md)
+2. [ROS Basics](Dokumentation/ROS2_Basics.md)
+3. [Sensoren](Dokumentation/Sensoren.md)
+4. [Navigation](Dokumentation/Navigation.md)
+
+---
+# Boards
+
+### Raspberry Pi 4 (Pi)
+
+*Der **Raspberry Pi 4** mit **4 GB RAM** dient als zentrale Recheneinheit des **TurtleBot 4** und übernimmt wesentliche Aufgaben wie die Verarbeitung von Sensordaten und die Steuerung der Roboterplattform. Ausgestattet mit einem **Quad-Core ARM Cortex-A72 Prozessor**, **Gigabit-Ethernet**, **WLAN** und **Bluetooth** bietet er eine vielseitige Grundlage für Anwendungen wie Navigation, Kartierung und Kommunikation. Die Integration von **ROS 2** ermöglicht eine einfache Entwicklung und Ausführung von Robotiksoftware, während GPIO-Pins und USB-Anschlüsse die Anbindung zusätzlicher Hardware erleichtern. Der Raspberry Pi 4 bildet damit das Kernstück für die Funktionalität und Erweiterbarkeit des TurtleBot 4.*
+
+##### GPIOs ansteuern unter Ubuntu 22.04
+###### Einrichten der Umgebung
+- Python 3 und Pip (der Python Paketmananger) müsssen installiert sein:`sudo apt install python3 python3-pip`
+- Das Paket *RPi.GPIO* installieren: `pip3 install RPi.GPIO`
+###### Beispiel: Eine LED blinken lassen mit dem Pi [led.py](../Code/RPi4(Python)/led.py)
+###### Unterscheidung Board- und BCM-Modus
+- Im **BOARD-Modus** (auch "physischer Modus" genannt) werden die Pins anhand ihrer **physischen Position auf der GPIO-Leiste** des Raspberry Pi adressiert.
+- Im **BCM-Modus** (Broadcom-Modus) werden die Pins anhand der **GPIO-Nummerierung des Broadcom-Chips** identifiziert.
+
+###### GPIO Belegung:
+
+<img src="https://www.raspberrypi.com/documentation/computers/images/GPIO-Pinout-Diagram-2.png" alt="GPIO Belegung" width="500">
+
+*[Quelle Bild](https://www.raspberrypi.com/documentation/computers/raspberry-pi.html)*
+
+### Raspberry Pi Pico (Pico)
+
+*Der **Raspberry Pi Pico** ist ein Mikrocontroller-Board, das auf dem speziell entwickelten **RP2040-Chip** basiert und ideal für Elektronik-, IoT- und Robotikprojekte ist. Es verfügt über einen **Dual-Core ARM Cortex-M0+ Prozessor**, 264 KB SRAM und 2 MB Flash-Speicher. Mit 26 GPIO-Pins, die Schnittstellen wie **I2C**, **SPI**, **UART** und **PWM** unterstützen, sowie einem **ADC** für analoge Eingaben, bietet der Pico vielseitige Anwendungsmöglichkeiten. Er wird über USB oder eine externe Stromquelle betrieben und kann mit **MicroPython** oder **C/C++** programmiert werden.
+
+Wir verwenden **Micropython** *
+
+- Micropython auf dem PICO installieren: [Anleitung + Download](https://www.raspberrypi.com/documentation/microcontrollers/micropython.html)
+- Micropython IDE für den PICO: [Thonny](https://thonny.org/)
+- In Thonny unter `Werkzeuge` -> `Optionen` -> `Interpreter` 'MicroPython (Raspberry Pi)' auswählen
+  <img src="/Bilder/thonny_interpreter.png" width="600">
+  
+  *Screenshot aus [Thonny](https://thonny.org/)*
+- Damit Code automatisch ausgeführt wird muss dieser auf dem Pico als `main.py` gespeichert werden
+
+Beispiele:
+- Die interne LED des Picos blinken lassen [interne_led.py](../Code/Pico(Micropython)/interne_led.py)
+- Eine externe LED blinken lassen mit dem Pico [externe_led.py](../Code/Pico(Micropython)/externe_led.py) + [Visualisierung des Aufbaus](https://wokwi.com/projects/418450844568127489)
+###### GPIO Belegung:
+
+<img src="https://www.raspberrypi.com/documentation/microcontrollers/images/pico2w-pinout.svg" alt="GPIO Belegung" width="600">
+
+
+*[Quelle Bild](https://www.raspberrypi.com/documentation/microcontrollers/pico-series.html)*
+
+# Externe Sensoren
+
+### HC-SR04
+*Ultraschall-Distanzsensor*
+
+<img src="https://botland.de/img/art/inne/16257_6.jpg" alt="HC_SR04" width="300">
+
+- Messbereich von 2 bis 400 cm
+- verwendet Ultraschallwellen um die Entfernung zu einem Objekt zu messen
+	1. Der Sensor sendet über den **Trigger-Pin** ein Ultraschallsignal (40 kHz) aus.
+	2. Das Signal trifft auf ein Objekt und wird reflektiert.
+	3. Der **Echo-Pin** misst die Zeit, die das Signal benötigt, um zurückzukehren.
+	4. Die Entfernung wird über die Schallgeschwindigkeit berechnet: $\text{Entfernung} = \frac{\text{Zeit} \times \text{Schallgeschwindigkeit}}{2}​$
+- mit dem Raspberry Pi 4 auslesen: [hc_sr04.py](../Code/RPi4(Python)/hc_sr04.py)
+- mit dem Raspberry Pi Pico auslesen: [hc_sr04.py](../Code/Pico(Micropython)/hc_sr04.py) + [Visualisierung des Aufbaus](https://wokwi.com/projects/418451470566981633)
+### TCRT5000
+*Infrarot-Reflexionssensor*
+
+<img src="https://buyzero.de/cdn/shop/products/TCRT5000TrackingSensorModule.jpg?v=1611750766" alt="TCRT5000" width="250">
+
+- sendet Infrarotlicht aus und erkennt das reflektierende Licht mit einem Fototransistor
+- liefert über den OUT-Pin ein digitales Signal: LOW *(0)* bei Hindernis (also reflektiertem Licht, zB. weißer Untergrund), HIGH *(1)* bei keinem Hindernis (kein reflektiertes Licht, zB. schwarzer Untergrund)
+- so kann man den Turtlebot beispielsweise einer Linie folgen lassen, daher auch Liniensensor
+- mit dem Raspberry Pi 4 auslesen: [TCRT5000.py](../Code/RPi4(Python)/TCRT5000.py)
+- mit dem Raspberry Pi Pico auslesen: [TCRT5000.py](../Code/Pico(Micropython)/TCRT5000.py)
+### HLK-LD2450
+*24-GHz-Radarsensor*
+
+<img src="https://m.media-amazon.com/images/I/51Xo7qKEsML._AC_UF894,1000_QL80_.jpg" alt="HLK-LD2450" width="300">
+
+- kompakter 24-GHz-Millimeterwellen-Radarsensor zur Bewegungserkennung und Zielverfolgung
+- misst Entfernung, Winkel und Geschwindigkeit von bis zu drei Zielen
+- UART Schnittstelle mit einer Datenrate von 256.000 Baud
+- Erkennungswinkel: Azimut ±60° *(horizontal)*, Elevation ±35° *(vertikal)*
+- Offizielle des Dokumentation des Herstellers auf [Google Drive](https://drive.google.com/drive/folders/1kTt0Z3hjKKrIF3OCIDGdwQ4KotDJ8SGA)
+
+# Interne Sensoren des TurtleBot 4
+
+### RPLIDAR A1M8
+*2D-LiDAR Sensor*
+
+<img src="https://www.mybotshop.de/media/image/product/105/lg/rplidar-a1m8-360-range-12m.jpg" alt="RPLIDAR A1M8" width="300">
+
+- 360° Abdeckung & Reichweite von 0,15m bis 12m
+- Abtastrate bis zu 8000 Samples pro Sekunde mit einer einstellbaren Drehgeschwindigkeit zwischen 5 Hz und 10 Hz
+- Messdaten lassen sich auf dem Turtlebot mit RViz2 visualieren und mit SLAM in eine Karte übersetzen
+### OAK-D Pro
+*Stereo Tiefenkamera mit Nachtsicht*
+
+<img src="https://www.generationrobots.com/17875-product_cover/luxonis-oak-d-pro-w-kamera.jpg" alt="oakd" width="300">
+
+- [Seite des Herstellers](https://docs.luxonis.com/hardware/products/OAK-D%20Pro)
+- speziell für neuronale Netzwerke und Echtzeitanwendungen optimiert und eignet sich so für Computer-Vision-Anwendungen
+- hat einen Intel Movidius Myriad X VPU integriert, der neuronale Netze direkt auf der Kamera ausführen kann
+- Der Hersteller stellt mit [Depth AI](https://github.com/luxonis/depthai-python) eine Plattform zur KI-gestützten Computer Vision für die Kamera bereit
+
+### Create 3 Sensoren
+Der Create 3 ist die Basis der Turtlebot4-Roboterplattform und beinhaltet die Antriebseinheit sowie einige Sensoren. Die Sensoren lassen sich in ROS auslesen.
+
+<img src="https://cdn-reichelt.de/bilder/web/xxl_ws/C900%2FMBS-ROB-27-2.png?type=ProductXxl&" alt="Create 3" width="300">
+
+#### 1. Bumper-Sensoren
+
+- **Funktion**: Erfassen Kollisionen mit der Vorderseite des Roboters und melden potenzielle Hindernisse. Diese Sensoren ermöglichen es dem Roboter, Zusammenstöße zu erkennen und seine Bewegung entsprechend anzupassen.
+- **Beispielnutzung**: `ros2 topic echo /hazard_detection`
+- **Beispielausgabe:**
+```
+detections:
+- header:
+    stamp:
+      sec: 1672531200
+      nanosec: 500000000
+    frame_id: "base_link"
+  type: 1  # HAZARD_BUMP
+
+```
+- **Beschreibung der Ausgabe**: Der Roboter meldet einen Zusammenstoß mit einem Hindernis.
+
+#### 2. Cliff-Sensoren
+- **Funktion**: Erkennen Absturzkanten oder Abgründe, um zu verhindern, dass der Roboter von einer erhöhten Fläche, wie einem Tisch oder einer Treppe, herunterfällt.
+- **Beispielnutzung**: `ros2 topic echo /hazard_detection`
+- **Beispielausgabe:**
+```
+detections:
+- header:
+    stamp:
+      sec: 1672531201
+      nanosec: 200000000
+    frame_id: "base_link"
+  type: 2  # HAZARD_CLIFF
+
+```
+- **Beschreibung der Ausgabe**: Der Roboter meldet eine Absturzkante und kann entsprechend reagieren.
+
+#### 3. Odometrie
+- **Funktion**: Liefert Informationen über die Position und Bewegung des Roboters. Die Odometrie-Daten helfen bei der Verfolgung der gefahrenen Strecke und Orientierung, um Navigation und Lokalisierung zu ermöglichen.
+- **Beispielnutzung**: `ros2 topic echo /odom`
+- **Beispielausgabe**:
+```
+header:
+  stamp:
+    sec: 1672531202
+    nanosec: 300000000
+  frame_id: "odom"
+pose:
+  pose:
+    position:
+      x: 1.23
+      y: 0.45
+      z: 0.0
+    orientation:
+      x: 0.0
+      y: 0.0
+      z: 0.707
+      w: 0.707
+
+```
+- **Beschreibung der Ausgabe**: Der Roboter befindet sich an Position (1.23, 0.45) mit einer Orientierung von 45 Grad.
+
+#### 4. IMU (Inertial Measurement Unit)
+- **Funktion**: Misst die Orientierung, Winkelgeschwindigkeit und lineare Beschleunigung des Roboters. Diese Daten werden genutzt, um Bewegungen und Neigungen zu analysieren sowie Stabilität und Richtung zu überwachen.
+- **Beispielnutzung**: `ros2 topic echo /imu`
+- **Beispielausgabe**:
+```
+header:
+  stamp:
+    sec: 1672531203
+    nanosec: 400000000
+  frame_id: "imu_link"
+orientation:
+  x: 0.0
+  y: 0.0
+  z: 0.707
+  w: 0.707
+angular_velocity:
+  x: 0.0
+  y: 0.0
+  z: 0.1
+linear_acceleration:
+  x: 0.0
+  y: -9.8
+  z: 0.0
+
+```
+- **Beschreibung der Ausgabe**: Der Roboter ist stabil, mit einer minimalen Winkelgeschwindigkeit und normaler Gravitation.
+
+#### 5. Wand-Sensor
+- **Funktion**: Misst die Entfernung zu einer Wand oder einem Hindernis in der Nähe. Dies ermöglicht es dem Roboter, entlang von Wänden zu navigieren oder Abstände zu Hindernissen zu halten.
+- **Beispielnutzung**: `ros2 topic echo /proximity`
+- **Beispielausgabe**:
+```
+header:
+  stamp:
+    sec: 1672531204
+    nanosec: 500000000
+  frame_id: "proximity_sensor"
+range: 0.25
+```
+- **Beschreibung der Ausgabe**: Der Roboter erkennt eine Wand oder ein Hindernis in einer Entfernung von 25 cm.
+
+#### 6. Batteriestatus
+- **Funktion**: Ãœberwacht den aktuellen Ladezustand der Batterie sowie andere Parameter wie Spannung und Strom. Diese Informationen helfen, den Energieverbrauch zu analysieren und die Betriebszeit zu optimieren.
+- **Beispielnutzung**: `ros2 topic echo /battery_state`
+- **Beispielausgabe**: 
+```
+header:
+  stamp:
+    sec: 1672531205
+    nanosec: 600000000
+  frame_id: "battery"
+voltage: 12.6
+current: -1.2
+percentage: 0.85
+```
+- **Beschreibung der Ausgabe**: Die Batterie hat eine Spannung von 12,6 V, eine negative Stromaufnahme (Entladung) von 1,2 A und ist zu 85 % geladen.
+
+# Auslagerung externer Sensoren mit dem Pico
+
+Um nicht die GPIO Pins des verbauten Pi belegen zu müssen bietet es sich an die externen Sensoren an einen Pico anzuschließen und diesen über USB mit dem Pi kommunizieren zu lassen.
+
+#### Beispiel: zwei Liniensensoren auslesen und anzeigen
+Mit [sensor_bridge_1.py](../Code/Pico(Micropython)/sensor_bridge_1.py) werden zwei Liniensensoren auf dem Pico ausgelesen und über die serielle USB Schnittstelle an den Pi weitergegeben. Damit dieser Code automatisch ausgeführt wird muss er allerdings als main.py auf dem Pico gespeichert werden. Mit [read_pico.py](../Code/RPi4(Python)/read_pico.py) lässt sich auf Seite des Pis das Signal dann auslesen.
+
+Dieses Prinzip der Auslagerung der Sensoren wird im nächsten Kapitel, der Navigation, wichtig sein.
diff --git a/Komponenten/README.md b/Komponenten/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..20760018b4eb6f4ab1018618da82a6a0ba731d41
--- /dev/null
+++ b/Komponenten/README.md
@@ -0,0 +1,12 @@
+
+##### Ãœbersicht zu den hier bereitgestellten CAD Datein
+
+<img src="/Bilder/komponenten.jpg" alt="Komponenten" width="800">
+
+##### Außerdem haben wir haben mit folgenden CAD Modellen aus dem Internet gearbeitet:
+- [*Tutlebot4*](https://github.com/turtlebot/turtlebot4-hardware/tree/master)
+- [*HC-SR04* Ultraschall Sensor](https://grabcad.com/library/hc-sr04-13)
+- [*HW-006-v1.3* Liniensensor](https://grabcad.com/library/reference-board-assembly-for-tcrt5000-infrarot-line-tracking-modul-hw-006-v1-3-1)
+- [*TCRT5000 Liniensensor*](https://grabcad.com/library/tcrt5000-2) 
+- [*Raspberry Pi Pico*](https://grabcad.com/library/raspberry-pi-pico-r3-1)
+- [*HLK-LD2450* Radar Sensor](https://grabcad.com/library/radar-sensor-module-hlk-ld2450-human-presence-motion-1)
diff --git a/Komponenten/arm 2.ipt b/Komponenten/arm 2.ipt
new file mode 100644
index 0000000000000000000000000000000000000000..8d587c30512ca698bf9d813dd82fc872438276d1
Binary files /dev/null and b/Komponenten/arm 2.ipt differ
diff --git a/Komponenten/arm 2.stp b/Komponenten/arm 2.stp
new file mode 100644
index 0000000000000000000000000000000000000000..c99f8f4aef2e3f6073341ecdc90f96843c430759
--- /dev/null
+++ b/Komponenten/arm 2.stp	
@@ -0,0 +1,727 @@
+ISO-10303-21;
+HEADER;
+/* Generated by software containing ST-Developer
+ * from STEP Tools, Inc. (www.steptools.com) 
+ */
+
+FILE_DESCRIPTION(
+/* description */ (''),
+/* implementation_level */ '2;1');
+
+FILE_NAME(
+/* name */ 'arm 2.stp',
+/* time_stamp */ '2025-01-13T19:50:31+01:00',
+/* author */ ('seb'),
+/* organization */ (''),
+/* preprocessor_version */ 'ST-DEVELOPER v20',
+/* originating_system */ 'Autodesk Inventor 2025',
+/* authorisation */ '');
+
+FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }'));
+ENDSEC;
+
+DATA;
+#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#643);
+#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#650,#12);
+#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#642);
+#13=STYLED_ITEM('',(#659),#14);
+#14=MANIFOLD_SOLID_BREP('Volumenk\X\F6rper1',#375);
+#15=CYLINDRICAL_SURFACE('',#405,7.5);
+#16=CYLINDRICAL_SURFACE('',#415,2.55);
+#17=CYLINDRICAL_SURFACE('',#419,10.);
+#18=CYLINDRICAL_SURFACE('',#422,10.);
+#19=CYLINDRICAL_SURFACE('',#424,2.25);
+#20=CYLINDRICAL_SURFACE('',#426,2.25);
+#21=LINE('',#547,#58);
+#22=LINE('',#549,#59);
+#23=LINE('',#550,#60);
+#24=LINE('',#554,#61);
+#25=LINE('',#555,#62);
+#26=LINE('',#556,#63);
+#27=LINE('',#559,#64);
+#28=LINE('',#561,#65);
+#29=LINE('',#563,#66);
+#30=LINE('',#564,#67);
+#31=LINE('',#566,#68);
+#32=LINE('',#568,#69);
+#33=LINE('',#573,#70);
+#34=LINE('',#575,#71);
+#35=LINE('',#577,#72);
+#36=LINE('',#578,#73);
+#37=LINE('',#582,#74);
+#38=LINE('',#583,#75);
+#39=LINE('',#585,#76);
+#40=LINE('',#586,#77);
+#41=LINE('',#589,#78);
+#42=LINE('',#591,#79);
+#43=LINE('',#593,#80);
+#44=LINE('',#594,#81);
+#45=LINE('',#597,#82);
+#46=LINE('',#600,#83);
+#47=LINE('',#610,#84);
+#48=LINE('',#615,#85);
+#49=LINE('',#618,#86);
+#50=LINE('',#622,#87);
+#51=LINE('',#626,#88);
+#52=LINE('',#628,#89);
+#53=LINE('',#631,#90);
+#54=LINE('',#632,#91);
+#55=LINE('',#635,#92);
+#56=LINE('',#636,#93);
+#57=LINE('',#638,#94);
+#58=VECTOR('',#443,10.);
+#59=VECTOR('',#444,10.);
+#60=VECTOR('',#445,10.);
+#61=VECTOR('',#448,10.);
+#62=VECTOR('',#449,10.);
+#63=VECTOR('',#450,10.);
+#64=VECTOR('',#453,10.);
+#65=VECTOR('',#454,10.);
+#66=VECTOR('',#455,10.);
+#67=VECTOR('',#456,10.);
+#68=VECTOR('',#459,7.5);
+#69=VECTOR('',#460,10.);
+#70=VECTOR('',#465,10.);
+#71=VECTOR('',#466,10.);
+#72=VECTOR('',#467,10.);
+#73=VECTOR('',#468,10.);
+#74=VECTOR('',#471,10.);
+#75=VECTOR('',#472,10.);
+#76=VECTOR('',#473,10.);
+#77=VECTOR('',#474,10.);
+#78=VECTOR('',#477,10.);
+#79=VECTOR('',#478,10.);
+#80=VECTOR('',#479,10.);
+#81=VECTOR('',#480,10.);
+#82=VECTOR('',#483,10.);
+#83=VECTOR('',#486,10.);
+#84=VECTOR('',#497,2.55);
+#85=VECTOR('',#504,10.);
+#86=VECTOR('',#509,10.);
+#87=VECTOR('',#514,10.);
+#88=VECTOR('',#519,2.25);
+#89=VECTOR('',#522,2.25);
+#90=VECTOR('',#525,10.);
+#91=VECTOR('',#526,10.);
+#92=VECTOR('',#529,10.);
+#93=VECTOR('',#530,10.);
+#94=VECTOR('',#533,10.);
+#95=FACE_BOUND('',#121,.T.);
+#96=FACE_BOUND('',#130,.T.);
+#97=FACE_BOUND('',#131,.T.);
+#98=FACE_BOUND('',#141,.T.);
+#99=FACE_BOUND('',#144,.T.);
+#100=FACE_OUTER_BOUND('',#120,.T.);
+#101=FACE_OUTER_BOUND('',#122,.T.);
+#102=FACE_OUTER_BOUND('',#123,.T.);
+#103=FACE_OUTER_BOUND('',#124,.T.);
+#104=FACE_OUTER_BOUND('',#125,.T.);
+#105=FACE_OUTER_BOUND('',#126,.T.);
+#106=FACE_OUTER_BOUND('',#127,.T.);
+#107=FACE_OUTER_BOUND('',#128,.T.);
+#108=FACE_OUTER_BOUND('',#129,.T.);
+#109=FACE_OUTER_BOUND('',#132,.T.);
+#110=FACE_OUTER_BOUND('',#133,.T.);
+#111=FACE_OUTER_BOUND('',#134,.T.);
+#112=FACE_OUTER_BOUND('',#135,.T.);
+#113=FACE_OUTER_BOUND('',#136,.T.);
+#114=FACE_OUTER_BOUND('',#137,.T.);
+#115=FACE_OUTER_BOUND('',#138,.T.);
+#116=FACE_OUTER_BOUND('',#139,.T.);
+#117=FACE_OUTER_BOUND('',#140,.T.);
+#118=FACE_OUTER_BOUND('',#142,.T.);
+#119=FACE_OUTER_BOUND('',#143,.T.);
+#120=EDGE_LOOP('',(#241));
+#121=EDGE_LOOP('',(#242));
+#122=EDGE_LOOP('',(#243,#244,#245,#246));
+#123=EDGE_LOOP('',(#247,#248,#249,#250));
+#124=EDGE_LOOP('',(#251,#252,#253,#254,#255,#256));
+#125=EDGE_LOOP('',(#257,#258,#259,#260,#261,#262,#263));
+#126=EDGE_LOOP('',(#264,#265,#266,#267));
+#127=EDGE_LOOP('',(#268,#269,#270,#271,#272));
+#128=EDGE_LOOP('',(#273,#274,#275,#276,#277,#278));
+#129=EDGE_LOOP('',(#279,#280,#281,#282,#283,#284,#285,#286));
+#130=EDGE_LOOP('',(#287));
+#131=EDGE_LOOP('',(#288));
+#132=EDGE_LOOP('',(#289,#290,#291,#292));
+#133=EDGE_LOOP('',(#293));
+#134=EDGE_LOOP('',(#294,#295,#296,#297));
+#135=EDGE_LOOP('',(#298,#299,#300,#301,#302,#303));
+#136=EDGE_LOOP('',(#304,#305,#306,#307));
+#137=EDGE_LOOP('',(#308,#309,#310,#311));
+#138=EDGE_LOOP('',(#312,#313,#314,#315));
+#139=EDGE_LOOP('',(#316,#317,#318,#319));
+#140=EDGE_LOOP('',(#320,#321,#322,#323));
+#141=EDGE_LOOP('',(#324));
+#142=EDGE_LOOP('',(#325,#326,#327,#328,#329,#330));
+#143=EDGE_LOOP('',(#331,#332,#333,#334,#335,#336,#337,#338,#339));
+#144=EDGE_LOOP('',(#340));
+#145=CIRCLE('',#399,7.5);
+#146=CIRCLE('',#400,2.25);
+#147=CIRCLE('',#402,7.5);
+#148=CIRCLE('',#406,7.5);
+#149=CIRCLE('',#411,10.);
+#150=CIRCLE('',#412,10.);
+#151=CIRCLE('',#413,2.25);
+#152=CIRCLE('',#414,2.25);
+#153=CIRCLE('',#416,2.55);
+#154=CIRCLE('',#417,2.55);
+#155=CIRCLE('',#420,10.);
+#156=CIRCLE('',#423,10.);
+#157=CIRCLE('',#425,2.25);
+#158=VERTEX_POINT('',#538);
+#159=VERTEX_POINT('',#540);
+#160=VERTEX_POINT('',#543);
+#161=VERTEX_POINT('',#544);
+#162=VERTEX_POINT('',#546);
+#163=VERTEX_POINT('',#548);
+#164=VERTEX_POINT('',#552);
+#165=VERTEX_POINT('',#553);
+#166=VERTEX_POINT('',#558);
+#167=VERTEX_POINT('',#560);
+#168=VERTEX_POINT('',#562);
+#169=VERTEX_POINT('',#567);
+#170=VERTEX_POINT('',#571);
+#171=VERTEX_POINT('',#572);
+#172=VERTEX_POINT('',#574);
+#173=VERTEX_POINT('',#576);
+#174=VERTEX_POINT('',#580);
+#175=VERTEX_POINT('',#581);
+#176=VERTEX_POINT('',#584);
+#177=VERTEX_POINT('',#588);
+#178=VERTEX_POINT('',#590);
+#179=VERTEX_POINT('',#592);
+#180=VERTEX_POINT('',#596);
+#181=VERTEX_POINT('',#599);
+#182=VERTEX_POINT('',#602);
+#183=VERTEX_POINT('',#604);
+#184=VERTEX_POINT('',#607);
+#185=VERTEX_POINT('',#609);
+#186=VERTEX_POINT('',#614);
+#187=VERTEX_POINT('',#620);
+#188=VERTEX_POINT('',#624);
+#189=VERTEX_POINT('',#630);
+#190=VERTEX_POINT('',#634);
+#191=EDGE_CURVE('',#158,#158,#145,.T.);
+#192=EDGE_CURVE('',#159,#159,#146,.T.);
+#193=EDGE_CURVE('',#160,#161,#147,.T.);
+#194=EDGE_CURVE('',#162,#161,#21,.T.);
+#195=EDGE_CURVE('',#163,#162,#22,.T.);
+#196=EDGE_CURVE('',#160,#163,#23,.T.);
+#197=EDGE_CURVE('',#164,#165,#24,.T.);
+#198=EDGE_CURVE('',#163,#164,#25,.T.);
+#199=EDGE_CURVE('',#165,#162,#26,.T.);
+#200=EDGE_CURVE('',#166,#161,#27,.T.);
+#201=EDGE_CURVE('',#166,#167,#28,.T.);
+#202=EDGE_CURVE('',#168,#167,#29,.T.);
+#203=EDGE_CURVE('',#165,#168,#30,.T.);
+#204=EDGE_CURVE('',#158,#161,#31,.T.);
+#205=EDGE_CURVE('',#169,#160,#32,.T.);
+#206=EDGE_CURVE('',#169,#166,#148,.T.);
+#207=EDGE_CURVE('',#170,#171,#33,.T.);
+#208=EDGE_CURVE('',#172,#170,#34,.T.);
+#209=EDGE_CURVE('',#172,#173,#35,.T.);
+#210=EDGE_CURVE('',#171,#173,#36,.T.);
+#211=EDGE_CURVE('',#174,#175,#37,.T.);
+#212=EDGE_CURVE('',#173,#174,#38,.T.);
+#213=EDGE_CURVE('',#176,#172,#39,.T.);
+#214=EDGE_CURVE('',#175,#176,#40,.T.);
+#215=EDGE_CURVE('',#170,#177,#41,.T.);
+#216=EDGE_CURVE('',#178,#177,#42,.T.);
+#217=EDGE_CURVE('',#179,#178,#43,.T.);
+#218=EDGE_CURVE('',#176,#179,#44,.T.);
+#219=EDGE_CURVE('',#180,#171,#45,.T.);
+#220=EDGE_CURVE('',#167,#180,#149,.T.);
+#221=EDGE_CURVE('',#181,#169,#46,.T.);
+#222=EDGE_CURVE('',#177,#181,#150,.T.);
+#223=EDGE_CURVE('',#182,#182,#151,.T.);
+#224=EDGE_CURVE('',#183,#183,#152,.T.);
+#225=EDGE_CURVE('',#184,#184,#153,.T.);
+#226=EDGE_CURVE('',#184,#185,#47,.T.);
+#227=EDGE_CURVE('',#185,#185,#154,.T.);
+#228=EDGE_CURVE('',#181,#186,#48,.T.);
+#229=EDGE_CURVE('',#186,#178,#155,.T.);
+#230=EDGE_CURVE('',#186,#164,#49,.T.);
+#231=EDGE_CURVE('',#187,#168,#156,.T.);
+#232=EDGE_CURVE('',#180,#187,#50,.T.);
+#233=EDGE_CURVE('',#188,#188,#157,.T.);
+#234=EDGE_CURVE('',#188,#183,#51,.T.);
+#235=EDGE_CURVE('',#159,#182,#52,.T.);
+#236=EDGE_CURVE('',#189,#179,#53,.T.);
+#237=EDGE_CURVE('',#175,#189,#54,.T.);
+#238=EDGE_CURVE('',#190,#189,#55,.T.);
+#239=EDGE_CURVE('',#174,#190,#56,.T.);
+#240=EDGE_CURVE('',#187,#190,#57,.T.);
+#241=ORIENTED_EDGE('',*,*,#191,.T.);
+#242=ORIENTED_EDGE('',*,*,#192,.T.);
+#243=ORIENTED_EDGE('',*,*,#193,.T.);
+#244=ORIENTED_EDGE('',*,*,#194,.F.);
+#245=ORIENTED_EDGE('',*,*,#195,.F.);
+#246=ORIENTED_EDGE('',*,*,#196,.F.);
+#247=ORIENTED_EDGE('',*,*,#197,.F.);
+#248=ORIENTED_EDGE('',*,*,#198,.F.);
+#249=ORIENTED_EDGE('',*,*,#195,.T.);
+#250=ORIENTED_EDGE('',*,*,#199,.F.);
+#251=ORIENTED_EDGE('',*,*,#199,.T.);
+#252=ORIENTED_EDGE('',*,*,#194,.T.);
+#253=ORIENTED_EDGE('',*,*,#200,.F.);
+#254=ORIENTED_EDGE('',*,*,#201,.T.);
+#255=ORIENTED_EDGE('',*,*,#202,.F.);
+#256=ORIENTED_EDGE('',*,*,#203,.F.);
+#257=ORIENTED_EDGE('',*,*,#191,.F.);
+#258=ORIENTED_EDGE('',*,*,#204,.T.);
+#259=ORIENTED_EDGE('',*,*,#193,.F.);
+#260=ORIENTED_EDGE('',*,*,#205,.F.);
+#261=ORIENTED_EDGE('',*,*,#206,.T.);
+#262=ORIENTED_EDGE('',*,*,#200,.T.);
+#263=ORIENTED_EDGE('',*,*,#204,.F.);
+#264=ORIENTED_EDGE('',*,*,#207,.F.);
+#265=ORIENTED_EDGE('',*,*,#208,.F.);
+#266=ORIENTED_EDGE('',*,*,#209,.T.);
+#267=ORIENTED_EDGE('',*,*,#210,.F.);
+#268=ORIENTED_EDGE('',*,*,#211,.F.);
+#269=ORIENTED_EDGE('',*,*,#212,.F.);
+#270=ORIENTED_EDGE('',*,*,#209,.F.);
+#271=ORIENTED_EDGE('',*,*,#213,.F.);
+#272=ORIENTED_EDGE('',*,*,#214,.F.);
+#273=ORIENTED_EDGE('',*,*,#213,.T.);
+#274=ORIENTED_EDGE('',*,*,#208,.T.);
+#275=ORIENTED_EDGE('',*,*,#215,.T.);
+#276=ORIENTED_EDGE('',*,*,#216,.F.);
+#277=ORIENTED_EDGE('',*,*,#217,.F.);
+#278=ORIENTED_EDGE('',*,*,#218,.F.);
+#279=ORIENTED_EDGE('',*,*,#207,.T.);
+#280=ORIENTED_EDGE('',*,*,#219,.F.);
+#281=ORIENTED_EDGE('',*,*,#220,.F.);
+#282=ORIENTED_EDGE('',*,*,#201,.F.);
+#283=ORIENTED_EDGE('',*,*,#206,.F.);
+#284=ORIENTED_EDGE('',*,*,#221,.F.);
+#285=ORIENTED_EDGE('',*,*,#222,.F.);
+#286=ORIENTED_EDGE('',*,*,#215,.F.);
+#287=ORIENTED_EDGE('',*,*,#223,.F.);
+#288=ORIENTED_EDGE('',*,*,#224,.F.);
+#289=ORIENTED_EDGE('',*,*,#225,.F.);
+#290=ORIENTED_EDGE('',*,*,#226,.T.);
+#291=ORIENTED_EDGE('',*,*,#227,.T.);
+#292=ORIENTED_EDGE('',*,*,#226,.F.);
+#293=ORIENTED_EDGE('',*,*,#227,.F.);
+#294=ORIENTED_EDGE('',*,*,#222,.T.);
+#295=ORIENTED_EDGE('',*,*,#228,.T.);
+#296=ORIENTED_EDGE('',*,*,#229,.T.);
+#297=ORIENTED_EDGE('',*,*,#216,.T.);
+#298=ORIENTED_EDGE('',*,*,#198,.T.);
+#299=ORIENTED_EDGE('',*,*,#230,.F.);
+#300=ORIENTED_EDGE('',*,*,#228,.F.);
+#301=ORIENTED_EDGE('',*,*,#221,.T.);
+#302=ORIENTED_EDGE('',*,*,#205,.T.);
+#303=ORIENTED_EDGE('',*,*,#196,.T.);
+#304=ORIENTED_EDGE('',*,*,#231,.T.);
+#305=ORIENTED_EDGE('',*,*,#202,.T.);
+#306=ORIENTED_EDGE('',*,*,#220,.T.);
+#307=ORIENTED_EDGE('',*,*,#232,.T.);
+#308=ORIENTED_EDGE('',*,*,#233,.F.);
+#309=ORIENTED_EDGE('',*,*,#234,.T.);
+#310=ORIENTED_EDGE('',*,*,#224,.T.);
+#311=ORIENTED_EDGE('',*,*,#234,.F.);
+#312=ORIENTED_EDGE('',*,*,#192,.F.);
+#313=ORIENTED_EDGE('',*,*,#235,.T.);
+#314=ORIENTED_EDGE('',*,*,#223,.T.);
+#315=ORIENTED_EDGE('',*,*,#235,.F.);
+#316=ORIENTED_EDGE('',*,*,#214,.T.);
+#317=ORIENTED_EDGE('',*,*,#218,.T.);
+#318=ORIENTED_EDGE('',*,*,#236,.F.);
+#319=ORIENTED_EDGE('',*,*,#237,.F.);
+#320=ORIENTED_EDGE('',*,*,#211,.T.);
+#321=ORIENTED_EDGE('',*,*,#237,.T.);
+#322=ORIENTED_EDGE('',*,*,#238,.F.);
+#323=ORIENTED_EDGE('',*,*,#239,.F.);
+#324=ORIENTED_EDGE('',*,*,#225,.T.);
+#325=ORIENTED_EDGE('',*,*,#212,.T.);
+#326=ORIENTED_EDGE('',*,*,#239,.T.);
+#327=ORIENTED_EDGE('',*,*,#240,.F.);
+#328=ORIENTED_EDGE('',*,*,#232,.F.);
+#329=ORIENTED_EDGE('',*,*,#219,.T.);
+#330=ORIENTED_EDGE('',*,*,#210,.T.);
+#331=ORIENTED_EDGE('',*,*,#197,.T.);
+#332=ORIENTED_EDGE('',*,*,#203,.T.);
+#333=ORIENTED_EDGE('',*,*,#231,.F.);
+#334=ORIENTED_EDGE('',*,*,#240,.T.);
+#335=ORIENTED_EDGE('',*,*,#238,.T.);
+#336=ORIENTED_EDGE('',*,*,#236,.T.);
+#337=ORIENTED_EDGE('',*,*,#217,.T.);
+#338=ORIENTED_EDGE('',*,*,#229,.F.);
+#339=ORIENTED_EDGE('',*,*,#230,.T.);
+#340=ORIENTED_EDGE('',*,*,#233,.T.);
+#341=PLANE('',#398);
+#342=PLANE('',#401);
+#343=PLANE('',#403);
+#344=PLANE('',#404);
+#345=PLANE('',#407);
+#346=PLANE('',#408);
+#347=PLANE('',#409);
+#348=PLANE('',#410);
+#349=PLANE('',#418);
+#350=PLANE('',#421);
+#351=PLANE('',#427);
+#352=PLANE('',#428);
+#353=PLANE('',#429);
+#354=PLANE('',#430);
+#355=ADVANCED_FACE('',(#100,#95),#341,.T.);
+#356=ADVANCED_FACE('',(#101),#342,.F.);
+#357=ADVANCED_FACE('',(#102),#343,.F.);
+#358=ADVANCED_FACE('',(#103),#344,.T.);
+#359=ADVANCED_FACE('',(#104),#15,.T.);
+#360=ADVANCED_FACE('',(#105),#345,.F.);
+#361=ADVANCED_FACE('',(#106),#346,.F.);
+#362=ADVANCED_FACE('',(#107),#347,.T.);
+#363=ADVANCED_FACE('',(#108,#96,#97),#348,.F.);
+#364=ADVANCED_FACE('',(#109),#16,.F.);
+#365=ADVANCED_FACE('',(#110),#349,.T.);
+#366=ADVANCED_FACE('',(#111),#17,.F.);
+#367=ADVANCED_FACE('',(#112),#350,.T.);
+#368=ADVANCED_FACE('',(#113),#18,.T.);
+#369=ADVANCED_FACE('',(#114),#19,.F.);
+#370=ADVANCED_FACE('',(#115),#20,.F.);
+#371=ADVANCED_FACE('',(#116),#351,.T.);
+#372=ADVANCED_FACE('',(#117,#98),#352,.T.);
+#373=ADVANCED_FACE('',(#118),#353,.T.);
+#374=ADVANCED_FACE('',(#119,#99),#354,.T.);
+#375=CLOSED_SHELL('',(#355,#356,#357,#358,#359,#360,#361,#362,#363,#364,
+#365,#366,#367,#368,#369,#370,#371,#372,#373,#374));
+#376=DERIVED_UNIT_ELEMENT(#379,1.);
+#377=DERIVED_UNIT_ELEMENT(#645,-3.);
+#378=DIMENSIONAL_EXPONENTS(0.,1.,0.,0.,0.,0.,0.);
+#379=(
+CONVERSION_BASED_UNIT('gram',#381)
+MASS_UNIT()
+NAMED_UNIT(#378)
+);
+#380=(
+MASS_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.KILO.,.GRAM.)
+);
+#381=MASS_MEASURE_WITH_UNIT(MASS_MEASURE(0.001),#380);
+#382=DERIVED_UNIT((#376,#377));
+#383=MEASURE_REPRESENTATION_ITEM('density measure',
+POSITIVE_RATIO_MEASURE(1.),#382);
+#384=PROPERTY_DEFINITION_REPRESENTATION(#389,#386);
+#385=PROPERTY_DEFINITION_REPRESENTATION(#390,#387);
+#386=REPRESENTATION('material name',(#388),#642);
+#387=REPRESENTATION('density',(#383),#642);
+#388=DESCRIPTIVE_REPRESENTATION_ITEM('Generisch','Generisch');
+#389=PROPERTY_DEFINITION('material property','material name',#652);
+#390=PROPERTY_DEFINITION('material property','density of part',#652);
+#391=DATE_TIME_ROLE('creation_date');
+#392=APPLIED_DATE_AND_TIME_ASSIGNMENT(#393,#391,(#652));
+#393=DATE_AND_TIME(#394,#395);
+#394=CALENDAR_DATE(2025,7,1);
+#395=LOCAL_TIME(0,0,0.,#396);
+#396=COORDINATED_UNIVERSAL_TIME_OFFSET(0,0,.BEHIND.);
+#397=AXIS2_PLACEMENT_3D('',#536,#431,#432);
+#398=AXIS2_PLACEMENT_3D('',#537,#433,#434);
+#399=AXIS2_PLACEMENT_3D('',#539,#435,#436);
+#400=AXIS2_PLACEMENT_3D('',#541,#437,#438);
+#401=AXIS2_PLACEMENT_3D('',#542,#439,#440);
+#402=AXIS2_PLACEMENT_3D('',#545,#441,#442);
+#403=AXIS2_PLACEMENT_3D('',#551,#446,#447);
+#404=AXIS2_PLACEMENT_3D('',#557,#451,#452);
+#405=AXIS2_PLACEMENT_3D('',#565,#457,#458);
+#406=AXIS2_PLACEMENT_3D('',#569,#461,#462);
+#407=AXIS2_PLACEMENT_3D('',#570,#463,#464);
+#408=AXIS2_PLACEMENT_3D('',#579,#469,#470);
+#409=AXIS2_PLACEMENT_3D('',#587,#475,#476);
+#410=AXIS2_PLACEMENT_3D('',#595,#481,#482);
+#411=AXIS2_PLACEMENT_3D('',#598,#484,#485);
+#412=AXIS2_PLACEMENT_3D('',#601,#487,#488);
+#413=AXIS2_PLACEMENT_3D('',#603,#489,#490);
+#414=AXIS2_PLACEMENT_3D('',#605,#491,#492);
+#415=AXIS2_PLACEMENT_3D('',#606,#493,#494);
+#416=AXIS2_PLACEMENT_3D('',#608,#495,#496);
+#417=AXIS2_PLACEMENT_3D('',#611,#498,#499);
+#418=AXIS2_PLACEMENT_3D('',#612,#500,#501);
+#419=AXIS2_PLACEMENT_3D('',#613,#502,#503);
+#420=AXIS2_PLACEMENT_3D('',#616,#505,#506);
+#421=AXIS2_PLACEMENT_3D('',#617,#507,#508);
+#422=AXIS2_PLACEMENT_3D('',#619,#510,#511);
+#423=AXIS2_PLACEMENT_3D('',#621,#512,#513);
+#424=AXIS2_PLACEMENT_3D('',#623,#515,#516);
+#425=AXIS2_PLACEMENT_3D('',#625,#517,#518);
+#426=AXIS2_PLACEMENT_3D('',#627,#520,#521);
+#427=AXIS2_PLACEMENT_3D('',#629,#523,#524);
+#428=AXIS2_PLACEMENT_3D('',#633,#527,#528);
+#429=AXIS2_PLACEMENT_3D('',#637,#531,#532);
+#430=AXIS2_PLACEMENT_3D('',#639,#534,#535);
+#431=DIRECTION('axis',(0.,0.,1.));
+#432=DIRECTION('refdir',(1.,0.,0.));
+#433=DIRECTION('center_axis',(0.,0.,1.));
+#434=DIRECTION('ref_axis',(1.,0.,0.));
+#435=DIRECTION('center_axis',(0.,0.,1.));
+#436=DIRECTION('ref_axis',(1.,0.,0.));
+#437=DIRECTION('center_axis',(0.,0.,-1.));
+#438=DIRECTION('ref_axis',(-1.,0.,0.));
+#439=DIRECTION('center_axis',(0.,0.,-1.));
+#440=DIRECTION('ref_axis',(-1.,0.,0.));
+#441=DIRECTION('center_axis',(0.,0.,-1.));
+#442=DIRECTION('ref_axis',(1.,0.,0.));
+#443=DIRECTION('',(-2.37841700325799E-16,1.,0.));
+#444=DIRECTION('',(-1.,0.,0.));
+#445=DIRECTION('',(1.66684162362104E-16,-1.,0.));
+#446=DIRECTION('center_axis',(0.,-1.,0.));
+#447=DIRECTION('ref_axis',(-1.,0.,0.));
+#448=DIRECTION('',(-1.,0.,0.));
+#449=DIRECTION('',(0.,0.,1.));
+#450=DIRECTION('',(0.,0.,-1.));
+#451=DIRECTION('center_axis',(-1.,-2.37841700325799E-16,0.));
+#452=DIRECTION('ref_axis',(2.37841700325799E-16,-1.,0.));
+#453=DIRECTION('',(0.,0.,1.));
+#454=DIRECTION('',(2.37841700325799E-16,-1.,0.));
+#455=DIRECTION('',(0.,0.,-1.));
+#456=DIRECTION('',(2.37841700325799E-16,-1.,0.));
+#457=DIRECTION('center_axis',(0.,0.,1.));
+#458=DIRECTION('ref_axis',(1.,0.,0.));
+#459=DIRECTION('',(0.,0.,-1.));
+#460=DIRECTION('',(0.,0.,1.));
+#461=DIRECTION('center_axis',(0.,0.,1.));
+#462=DIRECTION('ref_axis',(1.,0.,0.));
+#463=DIRECTION('center_axis',(-0.664129006508906,0.747617992502517,0.));
+#464=DIRECTION('ref_axis',(-0.747617992502517,-0.664129006508906,0.));
+#465=DIRECTION('',(-0.747617992502517,-0.664129006508906,0.));
+#466=DIRECTION('',(0.,0.,-1.));
+#467=DIRECTION('',(-0.747617992502517,-0.664129006508906,0.));
+#468=DIRECTION('',(0.,0.,1.));
+#469=DIRECTION('center_axis',(0.,0.,1.));
+#470=DIRECTION('ref_axis',(1.,0.,0.));
+#471=DIRECTION('',(0.978147600733805,0.20791169081776,0.));
+#472=DIRECTION('',(0.615661475325658,-0.788010753606722,0.));
+#473=DIRECTION('',(-0.664129006508906,0.747617992502517,0.));
+#474=DIRECTION('',(-0.207911690817761,0.978147600733805,0.));
+#475=DIRECTION('center_axis',(0.747617992502517,0.664129006508906,0.));
+#476=DIRECTION('ref_axis',(-0.664129006508906,0.747617992502517,0.));
+#477=DIRECTION('',(-0.664129006508906,0.747617992502517,0.));
+#478=DIRECTION('',(0.,0.,-1.));
+#479=DIRECTION('',(-0.664129006508906,0.747617992502517,0.));
+#480=DIRECTION('',(0.,0.,1.));
+#481=DIRECTION('center_axis',(0.,0.,1.));
+#482=DIRECTION('ref_axis',(1.,0.,0.));
+#483=DIRECTION('',(0.615661475325658,-0.788010753606722,0.));
+#484=DIRECTION('center_axis',(0.,0.,1.));
+#485=DIRECTION('ref_axis',(-0.945518575599317,-0.325568154457157,0.));
+#486=DIRECTION('',(-1.66684162362104E-16,1.,0.));
+#487=DIRECTION('center_axis',(0.,0.,-1.));
+#488=DIRECTION('ref_axis',(-0.934777511631114,-0.355233731152803,0.));
+#489=DIRECTION('center_axis',(0.,0.,-1.));
+#490=DIRECTION('ref_axis',(-1.,0.,0.));
+#491=DIRECTION('center_axis',(0.,0.,-1.));
+#492=DIRECTION('ref_axis',(-1.,0.,0.));
+#493=DIRECTION('center_axis',(-0.20791169081776,0.978147600733806,0.));
+#494=DIRECTION('ref_axis',(0.978147600733806,0.20791169081776,0.));
+#495=DIRECTION('center_axis',(-0.20791169081776,0.978147600733806,0.));
+#496=DIRECTION('ref_axis',(0.978147600733806,0.20791169081776,0.));
+#497=DIRECTION('',(-0.20791169081776,0.978147600733806,0.));
+#498=DIRECTION('center_axis',(-0.20791169081776,0.978147600733806,0.));
+#499=DIRECTION('ref_axis',(0.978147600733806,0.20791169081776,0.));
+#500=DIRECTION('center_axis',(0.20791169081776,-0.978147600733806,0.));
+#501=DIRECTION('ref_axis',(0.,0.,-1.));
+#502=DIRECTION('center_axis',(0.,0.,1.));
+#503=DIRECTION('ref_axis',(-0.934777511631114,-0.355233731152803,0.));
+#504=DIRECTION('',(0.,0.,1.));
+#505=DIRECTION('center_axis',(0.,0.,1.));
+#506=DIRECTION('ref_axis',(-0.934777511631114,-0.355233731152803,0.));
+#507=DIRECTION('center_axis',(1.,1.66684162362104E-16,0.));
+#508=DIRECTION('ref_axis',(-1.66684162362104E-16,1.,0.));
+#509=DIRECTION('',(-1.66684162362104E-16,1.,0.));
+#510=DIRECTION('center_axis',(0.,0.,1.));
+#511=DIRECTION('ref_axis',(-0.945518575599317,-0.325568154457157,0.));
+#512=DIRECTION('center_axis',(0.,0.,-1.));
+#513=DIRECTION('ref_axis',(-0.945518575599317,-0.325568154457157,0.));
+#514=DIRECTION('',(0.,0.,1.));
+#515=DIRECTION('center_axis',(0.,0.,1.));
+#516=DIRECTION('ref_axis',(-1.,0.,0.));
+#517=DIRECTION('center_axis',(0.,0.,-1.));
+#518=DIRECTION('ref_axis',(-1.,0.,0.));
+#519=DIRECTION('',(0.,0.,-1.));
+#520=DIRECTION('center_axis',(0.,0.,1.));
+#521=DIRECTION('ref_axis',(-1.,0.,0.));
+#522=DIRECTION('',(0.,0.,-1.));
+#523=DIRECTION('center_axis',(0.978147600733805,0.207911690817761,0.));
+#524=DIRECTION('ref_axis',(-0.207911690817761,0.978147600733805,0.));
+#525=DIRECTION('',(-0.207911690817761,0.978147600733805,0.));
+#526=DIRECTION('',(0.,0.,1.));
+#527=DIRECTION('center_axis',(0.20791169081776,-0.978147600733806,0.));
+#528=DIRECTION('ref_axis',(0.978147600733805,0.20791169081776,0.));
+#529=DIRECTION('',(0.978147600733805,0.20791169081776,0.));
+#530=DIRECTION('',(0.,0.,1.));
+#531=DIRECTION('center_axis',(-0.788010753606722,-0.615661475325658,0.));
+#532=DIRECTION('ref_axis',(0.615661475325658,-0.788010753606722,0.));
+#533=DIRECTION('',(0.615661475325658,-0.788010753606722,0.));
+#534=DIRECTION('center_axis',(0.,0.,1.));
+#535=DIRECTION('ref_axis',(1.,0.,0.));
+#536=CARTESIAN_POINT('',(0.,0.,0.));
+#537=CARTESIAN_POINT('Origin',(71.5957853224791,146.794558489098,10.));
+#538=CARTESIAN_POINT('',(64.0957853224791,146.794558489098,10.));
+#539=CARTESIAN_POINT('Origin',(71.5957853224791,146.794558489098,10.));
+#540=CARTESIAN_POINT('',(73.8457853224791,146.794558489098,10.));
+#541=CARTESIAN_POINT('Origin',(71.5957853224791,146.794558489098,10.));
+#542=CARTESIAN_POINT('Origin',(67.2787702831603,122.280067326334,6.));
+#543=CARTESIAN_POINT('',(79.0957853224791,146.794558489098,6.));
+#544=CARTESIAN_POINT('',(64.0957853224791,146.794558489098,6.));
+#545=CARTESIAN_POINT('Origin',(71.5957853224791,146.794558489098,6.));
+#546=CARTESIAN_POINT('',(64.0957853224791,77.4945584890983,6.));
+#547=CARTESIAN_POINT('',(64.0957853224791,134.537312907716,6.));
+#548=CARTESIAN_POINT('',(79.0957853224791,77.4945584890983,6.));
+#549=CARTESIAN_POINT('',(64.0957853224791,77.4945584890983,6.));
+#550=CARTESIAN_POINT('',(79.0957853224791,81.2522012862142,6.));
+#551=CARTESIAN_POINT('Origin',(79.0957853224791,77.4945584890983,10.));
+#552=CARTESIAN_POINT('',(79.0957853224791,77.4945584890983,10.));
+#553=CARTESIAN_POINT('',(64.0957853224791,77.4945584890983,10.));
+#554=CARTESIAN_POINT('',(88.9635618676938,77.4945584890983,10.));
+#555=CARTESIAN_POINT('',(79.0957853224791,77.4945584890983,5.));
+#556=CARTESIAN_POINT('',(64.0957853224791,77.4945584890983,5.));
+#557=CARTESIAN_POINT('Origin',(64.0957853224791,146.794558489098,0.));
+#558=CARTESIAN_POINT('',(64.0957853224791,146.794558489098,0.));
+#559=CARTESIAN_POINT('',(64.0957853224791,146.794558489098,0.));
+#560=CARTESIAN_POINT('',(64.0957853224792,38.2080578649985,0.));
+#561=CARTESIAN_POINT('',(64.0957853224791,146.794558489098,0.));
+#562=CARTESIAN_POINT('',(64.0957853224792,38.2080578649985,10.));
+#563=CARTESIAN_POINT('',(64.0957853224792,38.2080578649985,0.));
+#564=CARTESIAN_POINT('',(64.0957853224791,146.794558489098,10.));
+#565=CARTESIAN_POINT('Origin',(71.5957853224791,146.794558489098,0.));
+#566=CARTESIAN_POINT('',(64.0957853224791,146.794558489098,0.));
+#567=CARTESIAN_POINT('',(79.0957853224791,146.794558489098,0.));
+#568=CARTESIAN_POINT('',(79.0957853224791,146.794558489098,0.));
+#569=CARTESIAN_POINT('Origin',(71.5957853224791,146.794558489098,0.));
+#570=CARTESIAN_POINT('Origin',(115.864218077288,-1.16633074531083,0.));
+#571=CARTESIAN_POINT('',(115.864218077288,-1.16633074531084,0.));
+#572=CARTESIAN_POINT('',(101.876345949828,-13.5921307024363,0.));
+#573=CARTESIAN_POINT('',(126.155031393558,7.97527324555282,0.));
+#574=CARTESIAN_POINT('',(115.864218077288,-1.16633074531084,1.6));
+#575=CARTESIAN_POINT('',(115.864218077288,-1.16633074531083,0.));
+#576=CARTESIAN_POINT('',(101.876345949828,-13.5921307024363,1.6));
+#577=CARTESIAN_POINT('',(101.876345949828,-13.5921307024363,1.6));
+#578=CARTESIAN_POINT('',(101.876345949828,-13.5921307024363,0.));
+#579=CARTESIAN_POINT('Origin',(117.721618726583,-18.2704662497307,1.6));
+#580=CARTESIAN_POINT('',(118.894677492331,-35.3746017541505,1.6));
+#581=CARTESIAN_POINT('',(133.566891503338,-32.2559263918841,1.6));
+#582=CARTESIAN_POINT('',(120.07272183859,-35.1242006984149,1.6));
+#583=CARTESIAN_POINT('',(87.1238964706368,5.2901435628053,1.6));
+#584=CARTESIAN_POINT('',(130.448216141071,-17.583712380877,1.6));
+#585=CARTESIAN_POINT('',(127.812064651979,-14.6161650144883,1.6));
+#586=CARTESIAN_POINT('',(131.802317774205,-23.9542596954098,1.6));
+#587=CARTESIAN_POINT('Origin',(130.448216141071,-17.583712380877,0.));
+#588=CARTESIAN_POINT('',(81.619605397454,37.3832407006107,0.));
+#589=CARTESIAN_POINT('',(130.448216141071,-17.583712380877,0.));
+#590=CARTESIAN_POINT('',(81.619605397454,37.3832407006107,10.));
+#591=CARTESIAN_POINT('',(81.619605397454,37.3832407006107,0.));
+#592=CARTESIAN_POINT('',(130.448216141071,-17.583712380877,10.));
+#593=CARTESIAN_POINT('',(130.448216141071,-17.583712380877,10.));
+#594=CARTESIAN_POINT('',(130.448216141071,-17.583712380877,0.));
+#595=CARTESIAN_POINT('Origin',(98.8313384129085,59.4599783674739,0.));
+#596=CARTESIAN_POINT('',(66.2156777864119,32.0514431117419,0.));
+#597=CARTESIAN_POINT('',(64.0957853224792,34.7647817321019,0.));
+#598=CARTESIAN_POINT('Origin',(74.0957853224791,38.2080578649985,0.));
+#599=CARTESIAN_POINT('',(79.0957853224791,44.0245307656998,0.));
+#600=CARTESIAN_POINT('',(79.0957853224791,40.2243352460948,0.));
+#601=CARTESIAN_POINT('Origin',(89.0957853224791,44.0245307656998,0.));
+#602=CARTESIAN_POINT('',(73.8457853224791,146.794558489098,0.));
+#603=CARTESIAN_POINT('Origin',(71.5957853224791,146.794558489098,0.));
+#604=CARTESIAN_POINT('',(73.8457853224791,37.4945584890983,0.));
+#605=CARTESIAN_POINT('Origin',(71.5957853224791,37.4945584890983,0.));
+#606=CARTESIAN_POINT('Origin',(126.230784497834,-33.8152640730173,5.61941629196965));
+#607=CARTESIAN_POINT('',(123.736508115963,-34.3454388846026,5.61941629196965));
+#608=CARTESIAN_POINT('Origin',(126.230784497834,-33.8152640730173,5.61941629196965));
+#609=CARTESIAN_POINT('',(121.657391207786,-24.5639628772646,5.61941629196965));
+#610=CARTESIAN_POINT('',(123.736508115963,-34.3454388846026,5.61941629196965));
+#611=CARTESIAN_POINT('Origin',(124.151667589657,-24.0337880656793,5.61941629196965));
+#612=CARTESIAN_POINT('Origin',(124.151667589657,-24.0337880656793,5.61941629196965));
+#613=CARTESIAN_POINT('Origin',(89.0957853224791,44.0245307656998,0.));
+#614=CARTESIAN_POINT('',(79.0957853224791,44.0245307656998,10.));
+#615=CARTESIAN_POINT('',(79.0957853224791,44.0245307656998,0.));
+#616=CARTESIAN_POINT('Origin',(89.0957853224791,44.0245307656998,10.));
+#617=CARTESIAN_POINT('Origin',(79.0957853224791,40.2243352460948,0.));
+#618=CARTESIAN_POINT('',(79.0957853224791,40.2243352460948,10.));
+#619=CARTESIAN_POINT('Origin',(74.0957853224791,38.2080578649985,0.));
+#620=CARTESIAN_POINT('',(66.2156777864119,32.0514431117419,10.));
+#621=CARTESIAN_POINT('Origin',(74.0957853224791,38.2080578649985,10.));
+#622=CARTESIAN_POINT('',(66.2156777864119,32.0514431117419,0.));
+#623=CARTESIAN_POINT('Origin',(71.5957853224791,37.4945584890983,0.));
+#624=CARTESIAN_POINT('',(73.8457853224791,37.4945584890983,10.));
+#625=CARTESIAN_POINT('Origin',(71.5957853224791,37.4945584890983,10.));
+#626=CARTESIAN_POINT('',(73.8457853224791,37.4945584890983,0.));
+#627=CARTESIAN_POINT('Origin',(71.5957853224791,146.794558489098,0.));
+#628=CARTESIAN_POINT('',(73.8457853224791,146.794558489098,0.));
+#629=CARTESIAN_POINT('Origin',(133.566891503338,-32.2559263918841,0.));
+#630=CARTESIAN_POINT('',(133.566891503338,-32.2559263918841,10.));
+#631=CARTESIAN_POINT('',(133.566891503338,-32.2559263918841,10.));
+#632=CARTESIAN_POINT('',(133.566891503338,-32.2559263918841,0.));
+#633=CARTESIAN_POINT('Origin',(118.894677492331,-35.3746017541505,0.));
+#634=CARTESIAN_POINT('',(118.894677492331,-35.3746017541505,10.));
+#635=CARTESIAN_POINT('',(118.894677492331,-35.3746017541505,10.));
+#636=CARTESIAN_POINT('',(118.894677492331,-35.3746017541505,0.));
+#637=CARTESIAN_POINT('Origin',(64.0957853224792,34.7647817321019,0.));
+#638=CARTESIAN_POINT('',(64.0957853224792,34.7647817321019,10.));
+#639=CARTESIAN_POINT('Origin',(98.8313384129085,59.4599783674739,10.));
+#640=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#644,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#641=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#644,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#642=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#640))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#644,#646,#647))
+REPRESENTATION_CONTEXT('','3D')
+);
+#643=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#641))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#644,#646,#647))
+REPRESENTATION_CONTEXT('','3D')
+);
+#644=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.MILLI.,.METRE.)
+);
+#645=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.CENTI.,.METRE.)
+);
+#646=(
+NAMED_UNIT(*)
+PLANE_ANGLE_UNIT()
+SI_UNIT($,.RADIAN.)
+);
+#647=(
+NAMED_UNIT(*)
+SI_UNIT($,.STERADIAN.)
+SOLID_ANGLE_UNIT()
+);
+#648=SHAPE_DEFINITION_REPRESENTATION(#649,#650);
+#649=PRODUCT_DEFINITION_SHAPE('',$,#652);
+#650=SHAPE_REPRESENTATION('',(#397),#642);
+#651=PRODUCT_DEFINITION_CONTEXT('part definition',#656,'design');
+#652=PRODUCT_DEFINITION('arm 2','arm 2',#653,#651);
+#653=PRODUCT_DEFINITION_FORMATION('',$,#658);
+#654=PRODUCT_RELATED_PRODUCT_CATEGORY('arm 2','arm 2',(#658));
+#655=APPLICATION_PROTOCOL_DEFINITION('international standard',
+'automotive_design',2009,#656);
+#656=APPLICATION_CONTEXT(
+'Core Data for Automotive Mechanical Design Process');
+#657=PRODUCT_CONTEXT('part definition',#656,'mechanical');
+#658=PRODUCT('arm 2','arm 2',$,(#657));
+#659=PRESENTATION_STYLE_ASSIGNMENT((#660));
+#660=SURFACE_STYLE_USAGE(.BOTH.,#663);
+#661=SURFACE_STYLE_RENDERING_WITH_PROPERTIES($,#667,(#662));
+#662=SURFACE_STYLE_TRANSPARENT(0.);
+#663=SURFACE_SIDE_STYLE('',(#664,#661));
+#664=SURFACE_STYLE_FILL_AREA(#665);
+#665=FILL_AREA_STYLE('',(#666));
+#666=FILL_AREA_STYLE_COLOUR('',#667);
+#667=COLOUR_RGB('',0.749019607843137,0.749019607843137,0.749019607843137);
+ENDSEC;
+END-ISO-10303-21;
diff --git a/Komponenten/arm.ipt b/Komponenten/arm.ipt
new file mode 100644
index 0000000000000000000000000000000000000000..19eb25c04ed9ca1d8a63a66b0151bc9647aef6ad
Binary files /dev/null and b/Komponenten/arm.ipt differ
diff --git a/Komponenten/arm.stp b/Komponenten/arm.stp
new file mode 100644
index 0000000000000000000000000000000000000000..060ea0152811102171788684b3e2d53f691f2c47
--- /dev/null
+++ b/Komponenten/arm.stp
@@ -0,0 +1,1680 @@
+ISO-10303-21;
+HEADER;
+/* Generated by software containing ST-Developer
+ * from STEP Tools, Inc. (www.steptools.com) 
+ */
+
+FILE_DESCRIPTION(
+/* description */ (''),
+/* implementation_level */ '2;1');
+
+FILE_NAME(
+/* name */ 'arm.stp',
+/* time_stamp */ '2025-01-13T19:50:17+01:00',
+/* author */ ('seb'),
+/* organization */ (''),
+/* preprocessor_version */ 'ST-DEVELOPER v20',
+/* originating_system */ 'Autodesk Inventor 2025',
+/* authorisation */ '');
+
+FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }'));
+ENDSEC;
+
+DATA;
+#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#1587);
+#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#1594,#12);
+#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#1586);
+#13=STYLED_ITEM('',(#1603),#14);
+#14=MANIFOLD_SOLID_BREP('Volumenk\X\F6rper1',#907);
+#15=FACE_BOUND('',#316,.T.);
+#16=FACE_BOUND('',#332,.T.);
+#17=FACE_BOUND('',#333,.T.);
+#18=FACE_BOUND('',#336,.T.);
+#19=FACE_BOUND('',#349,.T.);
+#20=PLANE('',#974);
+#21=PLANE('',#975);
+#22=PLANE('',#977);
+#23=PLANE('',#978);
+#24=PLANE('',#979);
+#25=PLANE('',#982);
+#26=PLANE('',#1012);
+#27=PLANE('',#1013);
+#28=PLANE('',#1016);
+#29=PLANE('',#1017);
+#30=PLANE('',#1019);
+#31=PLANE('',#1020);
+#32=PLANE('',#1021);
+#33=PLANE('',#1022);
+#34=PLANE('',#1025);
+#35=PLANE('',#1028);
+#36=PLANE('',#1033);
+#37=PLANE('',#1034);
+#38=TOROIDAL_SURFACE('',#937,4.,2.);
+#39=TOROIDAL_SURFACE('',#948,4.,2.);
+#40=TOROIDAL_SURFACE('',#983,4.00000000000001,2.);
+#41=TOROIDAL_SURFACE('',#990,4.,2.);
+#42=ELLIPSE('',#935,2.82842712474619,2.);
+#43=ELLIPSE('',#936,2.16478440058479,2.);
+#44=ELLIPSE('',#943,2.16478440058479,2.);
+#45=ELLIPSE('',#954,2.82842712474618,2.);
+#46=ELLIPSE('',#961,2.16478440058479,2.);
+#47=ELLIPSE('',#968,2.8284271247462,2.);
+#48=ELLIPSE('',#988,2.1647844005848,2.);
+#49=ELLIPSE('',#989,2.82842712474619,2.);
+#50=ELLIPSE('',#996,2.16478440058479,2.);
+#51=ELLIPSE('',#999,2.57694101601104,2.);
+#52=ELLIPSE('',#1000,2.82842712474618,2.);
+#53=ELLIPSE('',#1003,2.8284271247462,2.);
+#54=ELLIPSE('',#1005,2.57694101601104,2.);
+#55=ELLIPSE('',#1007,2.16478440058479,2.);
+#56=ELLIPSE('',#1011,2.82842712474619,2.);
+#57=LINE('',#1335,#134);
+#58=LINE('',#1339,#135);
+#59=LINE('',#1352,#136);
+#60=LINE('',#1354,#137);
+#61=LINE('',#1374,#138);
+#62=LINE('',#1376,#139);
+#63=LINE('',#1386,#140);
+#64=LINE('',#1387,#141);
+#65=LINE('',#1390,#142);
+#66=LINE('',#1392,#143);
+#67=LINE('',#1395,#144);
+#68=LINE('',#1396,#145);
+#69=LINE('',#1398,#146);
+#70=LINE('',#1399,#147);
+#71=LINE('',#1401,#148);
+#72=LINE('',#1402,#149);
+#73=LINE('',#1404,#150);
+#74=LINE('',#1405,#151);
+#75=LINE('',#1407,#152);
+#76=LINE('',#1408,#153);
+#77=LINE('',#1411,#154);
+#78=LINE('',#1413,#155);
+#79=LINE('',#1416,#156);
+#80=LINE('',#1417,#157);
+#81=LINE('',#1422,#158);
+#82=LINE('',#1423,#159);
+#83=LINE('',#1429,#160);
+#84=LINE('',#1430,#161);
+#85=LINE('',#1431,#162);
+#86=LINE('',#1434,#163);
+#87=LINE('',#1436,#164);
+#88=LINE('',#1437,#165);
+#89=LINE('',#1439,#166);
+#90=LINE('',#1441,#167);
+#91=LINE('',#1443,#168);
+#92=LINE('',#1445,#169);
+#93=LINE('',#1447,#170);
+#94=LINE('',#1449,#171);
+#95=LINE('',#1451,#172);
+#96=LINE('',#1455,#173);
+#97=LINE('',#1456,#174);
+#98=LINE('',#1458,#175);
+#99=LINE('',#1460,#176);
+#100=LINE('',#1464,#177);
+#101=LINE('',#1468,#178);
+#102=LINE('',#1480,#179);
+#103=LINE('',#1484,#180);
+#104=LINE('',#1497,#181);
+#105=LINE('',#1499,#182);
+#106=LINE('',#1502,#183);
+#107=LINE('',#1503,#184);
+#108=LINE('',#1506,#185);
+#109=LINE('',#1508,#186);
+#110=LINE('',#1513,#187);
+#111=LINE('',#1514,#188);
+#112=LINE('',#1517,#189);
+#113=LINE('',#1519,#190);
+#114=LINE('',#1522,#191);
+#115=LINE('',#1526,#192);
+#116=LINE('',#1530,#193);
+#117=LINE('',#1533,#194);
+#118=LINE('',#1537,#195);
+#119=LINE('',#1539,#196);
+#120=LINE('',#1540,#197);
+#121=LINE('',#1542,#198);
+#122=LINE('',#1543,#199);
+#123=LINE('',#1549,#200);
+#124=LINE('',#1551,#201);
+#125=LINE('',#1555,#202);
+#126=LINE('',#1561,#203);
+#127=LINE('',#1562,#204);
+#128=LINE('',#1563,#205);
+#129=LINE('',#1567,#206);
+#130=LINE('',#1570,#207);
+#131=LINE('',#1571,#208);
+#132=LINE('',#1579,#209);
+#133=LINE('',#1581,#210);
+#134=VECTOR('',#1047,10.);
+#135=VECTOR('',#1050,10.);
+#136=VECTOR('',#1065,10.);
+#137=VECTOR('',#1066,10.);
+#138=VECTOR('',#1089,10.);
+#139=VECTOR('',#1090,10.);
+#140=VECTOR('',#1103,10.);
+#141=VECTOR('',#1104,10.);
+#142=VECTOR('',#1107,10.);
+#143=VECTOR('',#1108,10.);
+#144=VECTOR('',#1113,10.);
+#145=VECTOR('',#1114,10.);
+#146=VECTOR('',#1117,10.);
+#147=VECTOR('',#1118,10.);
+#148=VECTOR('',#1121,10.);
+#149=VECTOR('',#1122,10.);
+#150=VECTOR('',#1125,10.);
+#151=VECTOR('',#1126,10.);
+#152=VECTOR('',#1129,10.);
+#153=VECTOR('',#1130,10.);
+#154=VECTOR('',#1133,10.);
+#155=VECTOR('',#1134,10.);
+#156=VECTOR('',#1139,10.);
+#157=VECTOR('',#1140,10.);
+#158=VECTOR('',#1145,10.);
+#159=VECTOR('',#1146,10.);
+#160=VECTOR('',#1151,10.);
+#161=VECTOR('',#1152,10.);
+#162=VECTOR('',#1153,10.);
+#163=VECTOR('',#1156,10.);
+#164=VECTOR('',#1157,10.);
+#165=VECTOR('',#1158,10.);
+#166=VECTOR('',#1161,10.);
+#167=VECTOR('',#1162,10.);
+#168=VECTOR('',#1163,10.);
+#169=VECTOR('',#1164,10.);
+#170=VECTOR('',#1165,10.);
+#171=VECTOR('',#1166,10.);
+#172=VECTOR('',#1167,10.);
+#173=VECTOR('',#1170,10.);
+#174=VECTOR('',#1171,10.);
+#175=VECTOR('',#1174,10.);
+#176=VECTOR('',#1177,10.);
+#177=VECTOR('',#1180,10.);
+#178=VECTOR('',#1183,10.);
+#179=VECTOR('',#1198,10.);
+#180=VECTOR('',#1201,10.);
+#181=VECTOR('',#1216,10.);
+#182=VECTOR('',#1217,10.);
+#183=VECTOR('',#1222,10.);
+#184=VECTOR('',#1223,10.);
+#185=VECTOR('',#1226,10.);
+#186=VECTOR('',#1227,10.);
+#187=VECTOR('',#1234,10.);
+#188=VECTOR('',#1235,10.);
+#189=VECTOR('',#1238,10.);
+#190=VECTOR('',#1239,10.);
+#191=VECTOR('',#1244,10.);
+#192=VECTOR('',#1249,10.);
+#193=VECTOR('',#1254,10.);
+#194=VECTOR('',#1257,10.);
+#195=VECTOR('',#1262,10.);
+#196=VECTOR('',#1265,10.);
+#197=VECTOR('',#1266,10.);
+#198=VECTOR('',#1269,10.);
+#199=VECTOR('',#1270,10.);
+#200=VECTOR('',#1277,10.);
+#201=VECTOR('',#1280,10.);
+#202=VECTOR('',#1285,10.);
+#203=VECTOR('',#1292,10.);
+#204=VECTOR('',#1293,10.);
+#205=VECTOR('',#1294,10.);
+#206=VECTOR('',#1299,10.);
+#207=VECTOR('',#1302,10.);
+#208=VECTOR('',#1303,10.);
+#209=VECTOR('',#1316,2.5);
+#210=VECTOR('',#1319,2.5);
+#211=CYLINDRICAL_SURFACE('',#934,2.);
+#212=CYLINDRICAL_SURFACE('',#942,2.);
+#213=CYLINDRICAL_SURFACE('',#953,2.);
+#214=CYLINDRICAL_SURFACE('',#959,2.);
+#215=CYLINDRICAL_SURFACE('',#960,2.);
+#216=CYLINDRICAL_SURFACE('',#962,2.);
+#217=CYLINDRICAL_SURFACE('',#963,2.);
+#218=CYLINDRICAL_SURFACE('',#964,2.);
+#219=CYLINDRICAL_SURFACE('',#965,2.);
+#220=CYLINDRICAL_SURFACE('',#966,2.);
+#221=CYLINDRICAL_SURFACE('',#967,2.);
+#222=CYLINDRICAL_SURFACE('',#969,2.);
+#223=CYLINDRICAL_SURFACE('',#970,2.);
+#224=CYLINDRICAL_SURFACE('',#972,2.);
+#225=CYLINDRICAL_SURFACE('',#987,2.);
+#226=CYLINDRICAL_SURFACE('',#995,2.);
+#227=CYLINDRICAL_SURFACE('',#997,2.);
+#228=CYLINDRICAL_SURFACE('',#998,2.);
+#229=CYLINDRICAL_SURFACE('',#1001,2.);
+#230=CYLINDRICAL_SURFACE('',#1002,2.);
+#231=CYLINDRICAL_SURFACE('',#1004,2.);
+#232=CYLINDRICAL_SURFACE('',#1006,2.);
+#233=CYLINDRICAL_SURFACE('',#1008,2.);
+#234=CYLINDRICAL_SURFACE('',#1010,2.);
+#235=CYLINDRICAL_SURFACE('',#1023,2.5);
+#236=CYLINDRICAL_SURFACE('',#1026,2.5);
+#237=CYLINDRICAL_SURFACE('',#1031,2.5);
+#238=CYLINDRICAL_SURFACE('',#1032,2.5);
+#239=FACE_OUTER_BOUND('',#292,.T.);
+#240=FACE_OUTER_BOUND('',#293,.T.);
+#241=FACE_OUTER_BOUND('',#294,.T.);
+#242=FACE_OUTER_BOUND('',#295,.T.);
+#243=FACE_OUTER_BOUND('',#296,.T.);
+#244=FACE_OUTER_BOUND('',#297,.T.);
+#245=FACE_OUTER_BOUND('',#298,.T.);
+#246=FACE_OUTER_BOUND('',#299,.T.);
+#247=FACE_OUTER_BOUND('',#300,.T.);
+#248=FACE_OUTER_BOUND('',#301,.T.);
+#249=FACE_OUTER_BOUND('',#302,.T.);
+#250=FACE_OUTER_BOUND('',#303,.T.);
+#251=FACE_OUTER_BOUND('',#304,.T.);
+#252=FACE_OUTER_BOUND('',#305,.T.);
+#253=FACE_OUTER_BOUND('',#306,.T.);
+#254=FACE_OUTER_BOUND('',#307,.T.);
+#255=FACE_OUTER_BOUND('',#308,.T.);
+#256=FACE_OUTER_BOUND('',#309,.T.);
+#257=FACE_OUTER_BOUND('',#310,.T.);
+#258=FACE_OUTER_BOUND('',#311,.T.);
+#259=FACE_OUTER_BOUND('',#312,.T.);
+#260=FACE_OUTER_BOUND('',#313,.T.);
+#261=FACE_OUTER_BOUND('',#314,.T.);
+#262=FACE_OUTER_BOUND('',#315,.T.);
+#263=FACE_OUTER_BOUND('',#317,.T.);
+#264=FACE_OUTER_BOUND('',#318,.T.);
+#265=FACE_OUTER_BOUND('',#319,.T.);
+#266=FACE_OUTER_BOUND('',#320,.T.);
+#267=FACE_OUTER_BOUND('',#321,.T.);
+#268=FACE_OUTER_BOUND('',#322,.T.);
+#269=FACE_OUTER_BOUND('',#323,.T.);
+#270=FACE_OUTER_BOUND('',#324,.T.);
+#271=FACE_OUTER_BOUND('',#325,.T.);
+#272=FACE_OUTER_BOUND('',#326,.T.);
+#273=FACE_OUTER_BOUND('',#327,.T.);
+#274=FACE_OUTER_BOUND('',#328,.T.);
+#275=FACE_OUTER_BOUND('',#329,.T.);
+#276=FACE_OUTER_BOUND('',#330,.T.);
+#277=FACE_OUTER_BOUND('',#331,.T.);
+#278=FACE_OUTER_BOUND('',#334,.T.);
+#279=FACE_OUTER_BOUND('',#335,.T.);
+#280=FACE_OUTER_BOUND('',#337,.T.);
+#281=FACE_OUTER_BOUND('',#338,.T.);
+#282=FACE_OUTER_BOUND('',#339,.T.);
+#283=FACE_OUTER_BOUND('',#340,.T.);
+#284=FACE_OUTER_BOUND('',#341,.T.);
+#285=FACE_OUTER_BOUND('',#342,.T.);
+#286=FACE_OUTER_BOUND('',#343,.T.);
+#287=FACE_OUTER_BOUND('',#344,.T.);
+#288=FACE_OUTER_BOUND('',#345,.T.);
+#289=FACE_OUTER_BOUND('',#346,.T.);
+#290=FACE_OUTER_BOUND('',#347,.T.);
+#291=FACE_OUTER_BOUND('',#348,.T.);
+#292=EDGE_LOOP('',(#593,#594,#595));
+#293=EDGE_LOOP('',(#596,#597,#598,#599));
+#294=EDGE_LOOP('',(#600,#601,#602,#603));
+#295=EDGE_LOOP('',(#604,#605,#606,#607));
+#296=EDGE_LOOP('',(#608,#609,#610));
+#297=EDGE_LOOP('',(#611,#612,#613,#614));
+#298=EDGE_LOOP('',(#615,#616,#617,#618));
+#299=EDGE_LOOP('',(#619,#620,#621));
+#300=EDGE_LOOP('',(#622,#623,#624,#625));
+#301=EDGE_LOOP('',(#626,#627,#628,#629));
+#302=EDGE_LOOP('',(#630,#631,#632,#633));
+#303=EDGE_LOOP('',(#634,#635,#636,#637));
+#304=EDGE_LOOP('',(#638,#639,#640,#641));
+#305=EDGE_LOOP('',(#642,#643,#644,#645));
+#306=EDGE_LOOP('',(#646,#647,#648,#649));
+#307=EDGE_LOOP('',(#650,#651,#652,#653));
+#308=EDGE_LOOP('',(#654,#655,#656,#657));
+#309=EDGE_LOOP('',(#658,#659,#660,#661));
+#310=EDGE_LOOP('',(#662,#663,#664,#665,#666));
+#311=EDGE_LOOP('',(#667,#668,#669,#670));
+#312=EDGE_LOOP('',(#671,#672,#673,#674,#675,#676,#677,#678,#679,#680,#681,
+#682,#683,#684,#685,#686,#687));
+#313=EDGE_LOOP('',(#688,#689,#690,#691));
+#314=EDGE_LOOP('',(#692,#693,#694,#695));
+#315=EDGE_LOOP('',(#696,#697,#698,#699));
+#316=EDGE_LOOP('',(#700,#701,#702,#703));
+#317=EDGE_LOOP('',(#704,#705,#706,#707));
+#318=EDGE_LOOP('',(#708,#709,#710,#711));
+#319=EDGE_LOOP('',(#712,#713,#714,#715));
+#320=EDGE_LOOP('',(#716,#717,#718,#719));
+#321=EDGE_LOOP('',(#720,#721,#722,#723));
+#322=EDGE_LOOP('',(#724,#725,#726,#727));
+#323=EDGE_LOOP('',(#728,#729,#730,#731,#732));
+#324=EDGE_LOOP('',(#733,#734,#735,#736));
+#325=EDGE_LOOP('',(#737,#738,#739,#740));
+#326=EDGE_LOOP('',(#741,#742,#743,#744,#745));
+#327=EDGE_LOOP('',(#746,#747,#748,#749));
+#328=EDGE_LOOP('',(#750,#751,#752,#753));
+#329=EDGE_LOOP('',(#754,#755,#756,#757));
+#330=EDGE_LOOP('',(#758,#759,#760,#761,#762,#763,#764,#765,#766,#767,#768,
+#769,#770,#771,#772,#773));
+#331=EDGE_LOOP('',(#774,#775,#776,#777,#778,#779));
+#332=EDGE_LOOP('',(#780));
+#333=EDGE_LOOP('',(#781));
+#334=EDGE_LOOP('',(#782,#783,#784,#785));
+#335=EDGE_LOOP('',(#786,#787,#788,#789,#790));
+#336=EDGE_LOOP('',(#791));
+#337=EDGE_LOOP('',(#792,#793,#794,#795));
+#338=EDGE_LOOP('',(#796,#797,#798,#799));
+#339=EDGE_LOOP('',(#800,#801,#802,#803));
+#340=EDGE_LOOP('',(#804,#805,#806,#807));
+#341=EDGE_LOOP('',(#808,#809,#810,#811));
+#342=EDGE_LOOP('',(#812,#813,#814,#815));
+#343=EDGE_LOOP('',(#816,#817,#818,#819));
+#344=EDGE_LOOP('',(#820,#821,#822,#823,#824,#825,#826,#827));
+#345=EDGE_LOOP('',(#828,#829,#830,#831));
+#346=EDGE_LOOP('',(#832,#833,#834,#835,#836));
+#347=EDGE_LOOP('',(#837,#838,#839,#840));
+#348=EDGE_LOOP('',(#841,#842,#843,#844,#845,#846));
+#349=EDGE_LOOP('',(#847,#848,#849,#850));
+#350=CIRCLE('',#931,2.);
+#351=CIRCLE('',#932,2.);
+#352=CIRCLE('',#933,2.);
+#353=CIRCLE('',#938,2.);
+#354=CIRCLE('',#939,2.);
+#355=CIRCLE('',#940,2.);
+#356=CIRCLE('',#941,4.);
+#357=CIRCLE('',#945,2.);
+#358=CIRCLE('',#946,2.);
+#359=CIRCLE('',#947,2.);
+#360=CIRCLE('',#949,2.);
+#361=CIRCLE('',#950,2.);
+#362=CIRCLE('',#951,4.);
+#363=CIRCLE('',#952,2.);
+#364=CIRCLE('',#956,2.);
+#365=CIRCLE('',#957,2.);
+#366=CIRCLE('',#958,2.);
+#367=CIRCLE('',#971,2.);
+#368=CIRCLE('',#973,2.);
+#369=CIRCLE('',#976,3.99999999999999);
+#370=CIRCLE('',#980,2.5);
+#371=CIRCLE('',#981,2.5);
+#372=CIRCLE('',#984,2.);
+#373=CIRCLE('',#985,2.);
+#374=CIRCLE('',#986,2.);
+#375=CIRCLE('',#991,2.);
+#376=CIRCLE('',#992,2.);
+#377=CIRCLE('',#993,3.99999999999999);
+#378=CIRCLE('',#994,2.);
+#379=CIRCLE('',#1009,2.);
+#380=CIRCLE('',#1014,2.5);
+#381=CIRCLE('',#1015,2.5);
+#382=CIRCLE('',#1018,2.5);
+#383=CIRCLE('',#1024,2.5);
+#384=CIRCLE('',#1027,2.5);
+#385=CIRCLE('',#1029,2.5);
+#386=CIRCLE('',#1030,2.5);
+#387=VERTEX_POINT('',#1326);
+#388=VERTEX_POINT('',#1327);
+#389=VERTEX_POINT('',#1329);
+#390=VERTEX_POINT('',#1333);
+#391=VERTEX_POINT('',#1334);
+#392=VERTEX_POINT('',#1336);
+#393=VERTEX_POINT('',#1338);
+#394=VERTEX_POINT('',#1342);
+#395=VERTEX_POINT('',#1343);
+#396=VERTEX_POINT('',#1345);
+#397=VERTEX_POINT('',#1347);
+#398=VERTEX_POINT('',#1351);
+#399=VERTEX_POINT('',#1353);
+#400=VERTEX_POINT('',#1357);
+#401=VERTEX_POINT('',#1358);
+#402=VERTEX_POINT('',#1360);
+#403=VERTEX_POINT('',#1364);
+#404=VERTEX_POINT('',#1365);
+#405=VERTEX_POINT('',#1367);
+#406=VERTEX_POINT('',#1369);
+#407=VERTEX_POINT('',#1373);
+#408=VERTEX_POINT('',#1375);
+#409=VERTEX_POINT('',#1379);
+#410=VERTEX_POINT('',#1380);
+#411=VERTEX_POINT('',#1382);
+#412=VERTEX_POINT('',#1389);
+#413=VERTEX_POINT('',#1391);
+#414=VERTEX_POINT('',#1410);
+#415=VERTEX_POINT('',#1412);
+#416=VERTEX_POINT('',#1419);
+#417=VERTEX_POINT('',#1420);
+#418=VERTEX_POINT('',#1425);
+#419=VERTEX_POINT('',#1426);
+#420=VERTEX_POINT('',#1428);
+#421=VERTEX_POINT('',#1433);
+#422=VERTEX_POINT('',#1435);
+#423=VERTEX_POINT('',#1440);
+#424=VERTEX_POINT('',#1442);
+#425=VERTEX_POINT('',#1444);
+#426=VERTEX_POINT('',#1446);
+#427=VERTEX_POINT('',#1448);
+#428=VERTEX_POINT('',#1450);
+#429=VERTEX_POINT('',#1452);
+#430=VERTEX_POINT('',#1454);
+#431=VERTEX_POINT('',#1462);
+#432=VERTEX_POINT('',#1463);
+#433=VERTEX_POINT('',#1465);
+#434=VERTEX_POINT('',#1467);
+#435=VERTEX_POINT('',#1472);
+#436=VERTEX_POINT('',#1474);
+#437=VERTEX_POINT('',#1478);
+#438=VERTEX_POINT('',#1479);
+#439=VERTEX_POINT('',#1481);
+#440=VERTEX_POINT('',#1483);
+#441=VERTEX_POINT('',#1487);
+#442=VERTEX_POINT('',#1488);
+#443=VERTEX_POINT('',#1490);
+#444=VERTEX_POINT('',#1492);
+#445=VERTEX_POINT('',#1496);
+#446=VERTEX_POINT('',#1498);
+#447=VERTEX_POINT('',#1505);
+#448=VERTEX_POINT('',#1507);
+#449=VERTEX_POINT('',#1509);
+#450=VERTEX_POINT('',#1516);
+#451=VERTEX_POINT('',#1518);
+#452=VERTEX_POINT('',#1525);
+#453=VERTEX_POINT('',#1529);
+#454=VERTEX_POINT('',#1531);
+#455=VERTEX_POINT('',#1535);
+#456=VERTEX_POINT('',#1544);
+#457=VERTEX_POINT('',#1546);
+#458=VERTEX_POINT('',#1552);
+#459=VERTEX_POINT('',#1559);
+#460=VERTEX_POINT('',#1560);
+#461=VERTEX_POINT('',#1565);
+#462=VERTEX_POINT('',#1569);
+#463=VERTEX_POINT('',#1575);
+#464=EDGE_CURVE('',#387,#388,#350,.F.);
+#465=EDGE_CURVE('',#389,#387,#351,.F.);
+#466=EDGE_CURVE('',#388,#389,#352,.F.);
+#467=EDGE_CURVE('',#390,#391,#57,.T.);
+#468=EDGE_CURVE('',#391,#392,#42,.F.);
+#469=EDGE_CURVE('',#392,#393,#58,.T.);
+#470=EDGE_CURVE('',#393,#390,#43,.T.);
+#471=EDGE_CURVE('',#394,#395,#353,.T.);
+#472=EDGE_CURVE('',#396,#394,#354,.F.);
+#473=EDGE_CURVE('',#397,#396,#355,.T.);
+#474=EDGE_CURVE('',#397,#395,#356,.T.);
+#475=EDGE_CURVE('',#398,#389,#59,.T.);
+#476=EDGE_CURVE('',#387,#399,#60,.T.);
+#477=EDGE_CURVE('',#399,#398,#44,.T.);
+#478=EDGE_CURVE('',#400,#401,#357,.F.);
+#479=EDGE_CURVE('',#402,#400,#358,.F.);
+#480=EDGE_CURVE('',#401,#402,#359,.F.);
+#481=EDGE_CURVE('',#403,#404,#360,.F.);
+#482=EDGE_CURVE('',#405,#403,#361,.T.);
+#483=EDGE_CURVE('',#405,#406,#362,.T.);
+#484=EDGE_CURVE('',#404,#406,#363,.T.);
+#485=EDGE_CURVE('',#407,#405,#61,.T.);
+#486=EDGE_CURVE('',#403,#408,#62,.T.);
+#487=EDGE_CURVE('',#408,#407,#45,.T.);
+#488=EDGE_CURVE('',#409,#410,#364,.F.);
+#489=EDGE_CURVE('',#411,#409,#365,.F.);
+#490=EDGE_CURVE('',#410,#411,#366,.F.);
+#491=EDGE_CURVE('',#409,#404,#63,.T.);
+#492=EDGE_CURVE('',#406,#411,#64,.T.);
+#493=EDGE_CURVE('',#412,#410,#65,.T.);
+#494=EDGE_CURVE('',#411,#413,#66,.T.);
+#495=EDGE_CURVE('',#413,#412,#46,.T.);
+#496=EDGE_CURVE('',#400,#409,#67,.T.);
+#497=EDGE_CURVE('',#410,#402,#68,.T.);
+#498=EDGE_CURVE('',#399,#412,#69,.T.);
+#499=EDGE_CURVE('',#413,#398,#70,.T.);
+#500=EDGE_CURVE('',#394,#403,#71,.T.);
+#501=EDGE_CURVE('',#404,#396,#72,.T.);
+#502=EDGE_CURVE('',#393,#401,#73,.T.);
+#503=EDGE_CURVE('',#402,#390,#74,.T.);
+#504=EDGE_CURVE('',#401,#397,#75,.T.);
+#505=EDGE_CURVE('',#396,#400,#76,.T.);
+#506=EDGE_CURVE('',#414,#407,#77,.T.);
+#507=EDGE_CURVE('',#408,#415,#78,.T.);
+#508=EDGE_CURVE('',#415,#414,#47,.T.);
+#509=EDGE_CURVE('',#415,#394,#79,.T.);
+#510=EDGE_CURVE('',#395,#414,#80,.T.);
+#511=EDGE_CURVE('',#416,#417,#367,.T.);
+#512=EDGE_CURVE('',#417,#388,#81,.T.);
+#513=EDGE_CURVE('',#389,#416,#82,.T.);
+#514=EDGE_CURVE('',#418,#419,#368,.T.);
+#515=EDGE_CURVE('',#419,#420,#83,.T.);
+#516=EDGE_CURVE('',#420,#387,#84,.T.);
+#517=EDGE_CURVE('',#388,#418,#85,.T.);
+#518=EDGE_CURVE('',#421,#414,#86,.T.);
+#519=EDGE_CURVE('',#422,#421,#87,.T.);
+#520=EDGE_CURVE('',#422,#407,#88,.T.);
+#521=EDGE_CURVE('',#392,#419,#89,.T.);
+#522=EDGE_CURVE('',#418,#423,#90,.T.);
+#523=EDGE_CURVE('',#423,#424,#91,.T.);
+#524=EDGE_CURVE('',#424,#425,#92,.T.);
+#525=EDGE_CURVE('',#425,#426,#93,.T.);
+#526=EDGE_CURVE('',#427,#426,#94,.T.);
+#527=EDGE_CURVE('',#428,#427,#95,.T.);
+#528=EDGE_CURVE('',#429,#428,#369,.T.);
+#529=EDGE_CURVE('',#430,#429,#96,.T.);
+#530=EDGE_CURVE('',#430,#421,#97,.T.);
+#531=EDGE_CURVE('',#390,#412,#98,.T.);
+#532=EDGE_CURVE('',#399,#391,#99,.T.);
+#533=EDGE_CURVE('',#431,#432,#100,.T.);
+#534=EDGE_CURVE('',#432,#433,#370,.T.);
+#535=EDGE_CURVE('',#433,#434,#101,.T.);
+#536=EDGE_CURVE('',#434,#431,#371,.T.);
+#537=EDGE_CURVE('',#435,#428,#372,.T.);
+#538=EDGE_CURVE('',#436,#435,#373,.F.);
+#539=EDGE_CURVE('',#429,#436,#374,.T.);
+#540=EDGE_CURVE('',#437,#438,#102,.T.);
+#541=EDGE_CURVE('',#438,#439,#48,.T.);
+#542=EDGE_CURVE('',#439,#440,#103,.T.);
+#543=EDGE_CURVE('',#440,#437,#49,.T.);
+#544=EDGE_CURVE('',#441,#442,#375,.F.);
+#545=EDGE_CURVE('',#443,#441,#376,.T.);
+#546=EDGE_CURVE('',#443,#444,#377,.T.);
+#547=EDGE_CURVE('',#442,#444,#378,.T.);
+#548=EDGE_CURVE('',#445,#443,#104,.T.);
+#549=EDGE_CURVE('',#441,#446,#105,.T.);
+#550=EDGE_CURVE('',#446,#445,#50,.T.);
+#551=EDGE_CURVE('',#438,#445,#106,.T.);
+#552=EDGE_CURVE('',#446,#439,#107,.T.);
+#553=EDGE_CURVE('',#447,#442,#108,.T.);
+#554=EDGE_CURVE('',#444,#448,#109,.T.);
+#555=EDGE_CURVE('',#448,#449,#51,.T.);
+#556=EDGE_CURVE('',#449,#447,#52,.T.);
+#557=EDGE_CURVE('',#435,#441,#110,.T.);
+#558=EDGE_CURVE('',#442,#436,#111,.T.);
+#559=EDGE_CURVE('',#450,#447,#112,.T.);
+#560=EDGE_CURVE('',#449,#451,#113,.T.);
+#561=EDGE_CURVE('',#451,#450,#53,.T.);
+#562=EDGE_CURVE('',#436,#450,#114,.T.);
+#563=EDGE_CURVE('',#451,#430,#54,.T.);
+#564=EDGE_CURVE('',#452,#435,#115,.T.);
+#565=EDGE_CURVE('',#427,#452,#55,.T.);
+#566=EDGE_CURVE('',#440,#453,#116,.T.);
+#567=EDGE_CURVE('',#453,#454,#379,.T.);
+#568=EDGE_CURVE('',#454,#437,#117,.T.);
+#569=EDGE_CURVE('',#426,#455,#56,.F.);
+#570=EDGE_CURVE('',#455,#452,#118,.T.);
+#571=EDGE_CURVE('',#448,#422,#119,.T.);
+#572=EDGE_CURVE('',#416,#454,#120,.T.);
+#573=EDGE_CURVE('',#453,#424,#121,.T.);
+#574=EDGE_CURVE('',#417,#423,#122,.T.);
+#575=EDGE_CURVE('',#456,#456,#380,.T.);
+#576=EDGE_CURVE('',#457,#457,#381,.T.);
+#577=EDGE_CURVE('',#440,#425,#123,.T.);
+#578=EDGE_CURVE('',#455,#439,#124,.T.);
+#579=EDGE_CURVE('',#458,#458,#382,.T.);
+#580=EDGE_CURVE('',#446,#452,#125,.T.);
+#581=EDGE_CURVE('',#459,#460,#126,.T.);
+#582=EDGE_CURVE('',#432,#459,#127,.T.);
+#583=EDGE_CURVE('',#431,#460,#128,.T.);
+#584=EDGE_CURVE('',#460,#461,#383,.T.);
+#585=EDGE_CURVE('',#434,#461,#129,.T.);
+#586=EDGE_CURVE('',#461,#462,#130,.T.);
+#587=EDGE_CURVE('',#433,#462,#131,.T.);
+#588=EDGE_CURVE('',#462,#459,#384,.T.);
+#589=EDGE_CURVE('',#420,#463,#385,.T.);
+#590=EDGE_CURVE('',#463,#420,#386,.T.);
+#591=EDGE_CURVE('',#457,#458,#132,.T.);
+#592=EDGE_CURVE('',#456,#463,#133,.T.);
+#593=ORIENTED_EDGE('',*,*,#464,.F.);
+#594=ORIENTED_EDGE('',*,*,#465,.F.);
+#595=ORIENTED_EDGE('',*,*,#466,.F.);
+#596=ORIENTED_EDGE('',*,*,#467,.T.);
+#597=ORIENTED_EDGE('',*,*,#468,.T.);
+#598=ORIENTED_EDGE('',*,*,#469,.T.);
+#599=ORIENTED_EDGE('',*,*,#470,.T.);
+#600=ORIENTED_EDGE('',*,*,#471,.F.);
+#601=ORIENTED_EDGE('',*,*,#472,.F.);
+#602=ORIENTED_EDGE('',*,*,#473,.F.);
+#603=ORIENTED_EDGE('',*,*,#474,.T.);
+#604=ORIENTED_EDGE('',*,*,#475,.T.);
+#605=ORIENTED_EDGE('',*,*,#465,.T.);
+#606=ORIENTED_EDGE('',*,*,#476,.T.);
+#607=ORIENTED_EDGE('',*,*,#477,.T.);
+#608=ORIENTED_EDGE('',*,*,#478,.F.);
+#609=ORIENTED_EDGE('',*,*,#479,.F.);
+#610=ORIENTED_EDGE('',*,*,#480,.F.);
+#611=ORIENTED_EDGE('',*,*,#481,.F.);
+#612=ORIENTED_EDGE('',*,*,#482,.F.);
+#613=ORIENTED_EDGE('',*,*,#483,.T.);
+#614=ORIENTED_EDGE('',*,*,#484,.F.);
+#615=ORIENTED_EDGE('',*,*,#485,.T.);
+#616=ORIENTED_EDGE('',*,*,#482,.T.);
+#617=ORIENTED_EDGE('',*,*,#486,.T.);
+#618=ORIENTED_EDGE('',*,*,#487,.T.);
+#619=ORIENTED_EDGE('',*,*,#488,.F.);
+#620=ORIENTED_EDGE('',*,*,#489,.F.);
+#621=ORIENTED_EDGE('',*,*,#490,.F.);
+#622=ORIENTED_EDGE('',*,*,#489,.T.);
+#623=ORIENTED_EDGE('',*,*,#491,.T.);
+#624=ORIENTED_EDGE('',*,*,#484,.T.);
+#625=ORIENTED_EDGE('',*,*,#492,.T.);
+#626=ORIENTED_EDGE('',*,*,#493,.T.);
+#627=ORIENTED_EDGE('',*,*,#490,.T.);
+#628=ORIENTED_EDGE('',*,*,#494,.T.);
+#629=ORIENTED_EDGE('',*,*,#495,.T.);
+#630=ORIENTED_EDGE('',*,*,#479,.T.);
+#631=ORIENTED_EDGE('',*,*,#496,.T.);
+#632=ORIENTED_EDGE('',*,*,#488,.T.);
+#633=ORIENTED_EDGE('',*,*,#497,.T.);
+#634=ORIENTED_EDGE('',*,*,#498,.T.);
+#635=ORIENTED_EDGE('',*,*,#495,.F.);
+#636=ORIENTED_EDGE('',*,*,#499,.T.);
+#637=ORIENTED_EDGE('',*,*,#477,.F.);
+#638=ORIENTED_EDGE('',*,*,#472,.T.);
+#639=ORIENTED_EDGE('',*,*,#500,.T.);
+#640=ORIENTED_EDGE('',*,*,#481,.T.);
+#641=ORIENTED_EDGE('',*,*,#501,.T.);
+#642=ORIENTED_EDGE('',*,*,#502,.T.);
+#643=ORIENTED_EDGE('',*,*,#480,.T.);
+#644=ORIENTED_EDGE('',*,*,#503,.T.);
+#645=ORIENTED_EDGE('',*,*,#470,.F.);
+#646=ORIENTED_EDGE('',*,*,#478,.T.);
+#647=ORIENTED_EDGE('',*,*,#504,.T.);
+#648=ORIENTED_EDGE('',*,*,#473,.T.);
+#649=ORIENTED_EDGE('',*,*,#505,.T.);
+#650=ORIENTED_EDGE('',*,*,#506,.T.);
+#651=ORIENTED_EDGE('',*,*,#487,.F.);
+#652=ORIENTED_EDGE('',*,*,#507,.T.);
+#653=ORIENTED_EDGE('',*,*,#508,.T.);
+#654=ORIENTED_EDGE('',*,*,#509,.T.);
+#655=ORIENTED_EDGE('',*,*,#471,.T.);
+#656=ORIENTED_EDGE('',*,*,#510,.T.);
+#657=ORIENTED_EDGE('',*,*,#508,.F.);
+#658=ORIENTED_EDGE('',*,*,#511,.T.);
+#659=ORIENTED_EDGE('',*,*,#512,.T.);
+#660=ORIENTED_EDGE('',*,*,#466,.T.);
+#661=ORIENTED_EDGE('',*,*,#513,.T.);
+#662=ORIENTED_EDGE('',*,*,#514,.T.);
+#663=ORIENTED_EDGE('',*,*,#515,.T.);
+#664=ORIENTED_EDGE('',*,*,#516,.T.);
+#665=ORIENTED_EDGE('',*,*,#464,.T.);
+#666=ORIENTED_EDGE('',*,*,#517,.T.);
+#667=ORIENTED_EDGE('',*,*,#506,.F.);
+#668=ORIENTED_EDGE('',*,*,#518,.F.);
+#669=ORIENTED_EDGE('',*,*,#519,.F.);
+#670=ORIENTED_EDGE('',*,*,#520,.T.);
+#671=ORIENTED_EDGE('',*,*,#510,.F.);
+#672=ORIENTED_EDGE('',*,*,#474,.F.);
+#673=ORIENTED_EDGE('',*,*,#504,.F.);
+#674=ORIENTED_EDGE('',*,*,#502,.F.);
+#675=ORIENTED_EDGE('',*,*,#469,.F.);
+#676=ORIENTED_EDGE('',*,*,#521,.T.);
+#677=ORIENTED_EDGE('',*,*,#514,.F.);
+#678=ORIENTED_EDGE('',*,*,#522,.T.);
+#679=ORIENTED_EDGE('',*,*,#523,.T.);
+#680=ORIENTED_EDGE('',*,*,#524,.T.);
+#681=ORIENTED_EDGE('',*,*,#525,.T.);
+#682=ORIENTED_EDGE('',*,*,#526,.F.);
+#683=ORIENTED_EDGE('',*,*,#527,.F.);
+#684=ORIENTED_EDGE('',*,*,#528,.F.);
+#685=ORIENTED_EDGE('',*,*,#529,.F.);
+#686=ORIENTED_EDGE('',*,*,#530,.T.);
+#687=ORIENTED_EDGE('',*,*,#518,.T.);
+#688=ORIENTED_EDGE('',*,*,#503,.F.);
+#689=ORIENTED_EDGE('',*,*,#497,.F.);
+#690=ORIENTED_EDGE('',*,*,#493,.F.);
+#691=ORIENTED_EDGE('',*,*,#531,.F.);
+#692=ORIENTED_EDGE('',*,*,#467,.F.);
+#693=ORIENTED_EDGE('',*,*,#531,.T.);
+#694=ORIENTED_EDGE('',*,*,#498,.F.);
+#695=ORIENTED_EDGE('',*,*,#532,.T.);
+#696=ORIENTED_EDGE('',*,*,#486,.F.);
+#697=ORIENTED_EDGE('',*,*,#500,.F.);
+#698=ORIENTED_EDGE('',*,*,#509,.F.);
+#699=ORIENTED_EDGE('',*,*,#507,.F.);
+#700=ORIENTED_EDGE('',*,*,#533,.T.);
+#701=ORIENTED_EDGE('',*,*,#534,.T.);
+#702=ORIENTED_EDGE('',*,*,#535,.T.);
+#703=ORIENTED_EDGE('',*,*,#536,.T.);
+#704=ORIENTED_EDGE('',*,*,#491,.F.);
+#705=ORIENTED_EDGE('',*,*,#496,.F.);
+#706=ORIENTED_EDGE('',*,*,#505,.F.);
+#707=ORIENTED_EDGE('',*,*,#501,.F.);
+#708=ORIENTED_EDGE('',*,*,#537,.F.);
+#709=ORIENTED_EDGE('',*,*,#538,.F.);
+#710=ORIENTED_EDGE('',*,*,#539,.F.);
+#711=ORIENTED_EDGE('',*,*,#528,.T.);
+#712=ORIENTED_EDGE('',*,*,#540,.T.);
+#713=ORIENTED_EDGE('',*,*,#541,.T.);
+#714=ORIENTED_EDGE('',*,*,#542,.T.);
+#715=ORIENTED_EDGE('',*,*,#543,.T.);
+#716=ORIENTED_EDGE('',*,*,#544,.F.);
+#717=ORIENTED_EDGE('',*,*,#545,.F.);
+#718=ORIENTED_EDGE('',*,*,#546,.T.);
+#719=ORIENTED_EDGE('',*,*,#547,.F.);
+#720=ORIENTED_EDGE('',*,*,#548,.T.);
+#721=ORIENTED_EDGE('',*,*,#545,.T.);
+#722=ORIENTED_EDGE('',*,*,#549,.T.);
+#723=ORIENTED_EDGE('',*,*,#550,.T.);
+#724=ORIENTED_EDGE('',*,*,#551,.T.);
+#725=ORIENTED_EDGE('',*,*,#550,.F.);
+#726=ORIENTED_EDGE('',*,*,#552,.T.);
+#727=ORIENTED_EDGE('',*,*,#541,.F.);
+#728=ORIENTED_EDGE('',*,*,#553,.T.);
+#729=ORIENTED_EDGE('',*,*,#547,.T.);
+#730=ORIENTED_EDGE('',*,*,#554,.T.);
+#731=ORIENTED_EDGE('',*,*,#555,.T.);
+#732=ORIENTED_EDGE('',*,*,#556,.T.);
+#733=ORIENTED_EDGE('',*,*,#538,.T.);
+#734=ORIENTED_EDGE('',*,*,#557,.T.);
+#735=ORIENTED_EDGE('',*,*,#544,.T.);
+#736=ORIENTED_EDGE('',*,*,#558,.T.);
+#737=ORIENTED_EDGE('',*,*,#559,.T.);
+#738=ORIENTED_EDGE('',*,*,#556,.F.);
+#739=ORIENTED_EDGE('',*,*,#560,.T.);
+#740=ORIENTED_EDGE('',*,*,#561,.T.);
+#741=ORIENTED_EDGE('',*,*,#529,.T.);
+#742=ORIENTED_EDGE('',*,*,#539,.T.);
+#743=ORIENTED_EDGE('',*,*,#562,.T.);
+#744=ORIENTED_EDGE('',*,*,#561,.F.);
+#745=ORIENTED_EDGE('',*,*,#563,.T.);
+#746=ORIENTED_EDGE('',*,*,#564,.T.);
+#747=ORIENTED_EDGE('',*,*,#537,.T.);
+#748=ORIENTED_EDGE('',*,*,#527,.T.);
+#749=ORIENTED_EDGE('',*,*,#565,.T.);
+#750=ORIENTED_EDGE('',*,*,#566,.T.);
+#751=ORIENTED_EDGE('',*,*,#567,.T.);
+#752=ORIENTED_EDGE('',*,*,#568,.T.);
+#753=ORIENTED_EDGE('',*,*,#543,.F.);
+#754=ORIENTED_EDGE('',*,*,#526,.T.);
+#755=ORIENTED_EDGE('',*,*,#569,.T.);
+#756=ORIENTED_EDGE('',*,*,#570,.T.);
+#757=ORIENTED_EDGE('',*,*,#565,.F.);
+#758=ORIENTED_EDGE('',*,*,#485,.F.);
+#759=ORIENTED_EDGE('',*,*,#520,.F.);
+#760=ORIENTED_EDGE('',*,*,#571,.F.);
+#761=ORIENTED_EDGE('',*,*,#554,.F.);
+#762=ORIENTED_EDGE('',*,*,#546,.F.);
+#763=ORIENTED_EDGE('',*,*,#548,.F.);
+#764=ORIENTED_EDGE('',*,*,#551,.F.);
+#765=ORIENTED_EDGE('',*,*,#540,.F.);
+#766=ORIENTED_EDGE('',*,*,#568,.F.);
+#767=ORIENTED_EDGE('',*,*,#572,.F.);
+#768=ORIENTED_EDGE('',*,*,#513,.F.);
+#769=ORIENTED_EDGE('',*,*,#475,.F.);
+#770=ORIENTED_EDGE('',*,*,#499,.F.);
+#771=ORIENTED_EDGE('',*,*,#494,.F.);
+#772=ORIENTED_EDGE('',*,*,#492,.F.);
+#773=ORIENTED_EDGE('',*,*,#483,.F.);
+#774=ORIENTED_EDGE('',*,*,#511,.F.);
+#775=ORIENTED_EDGE('',*,*,#572,.T.);
+#776=ORIENTED_EDGE('',*,*,#567,.F.);
+#777=ORIENTED_EDGE('',*,*,#573,.T.);
+#778=ORIENTED_EDGE('',*,*,#523,.F.);
+#779=ORIENTED_EDGE('',*,*,#574,.F.);
+#780=ORIENTED_EDGE('',*,*,#575,.T.);
+#781=ORIENTED_EDGE('',*,*,#576,.T.);
+#782=ORIENTED_EDGE('',*,*,#566,.F.);
+#783=ORIENTED_EDGE('',*,*,#577,.T.);
+#784=ORIENTED_EDGE('',*,*,#524,.F.);
+#785=ORIENTED_EDGE('',*,*,#573,.F.);
+#786=ORIENTED_EDGE('',*,*,#542,.F.);
+#787=ORIENTED_EDGE('',*,*,#578,.F.);
+#788=ORIENTED_EDGE('',*,*,#569,.F.);
+#789=ORIENTED_EDGE('',*,*,#525,.F.);
+#790=ORIENTED_EDGE('',*,*,#577,.F.);
+#791=ORIENTED_EDGE('',*,*,#579,.T.);
+#792=ORIENTED_EDGE('',*,*,#549,.F.);
+#793=ORIENTED_EDGE('',*,*,#557,.F.);
+#794=ORIENTED_EDGE('',*,*,#564,.F.);
+#795=ORIENTED_EDGE('',*,*,#580,.F.);
+#796=ORIENTED_EDGE('',*,*,#552,.F.);
+#797=ORIENTED_EDGE('',*,*,#580,.T.);
+#798=ORIENTED_EDGE('',*,*,#570,.F.);
+#799=ORIENTED_EDGE('',*,*,#578,.T.);
+#800=ORIENTED_EDGE('',*,*,#553,.F.);
+#801=ORIENTED_EDGE('',*,*,#559,.F.);
+#802=ORIENTED_EDGE('',*,*,#562,.F.);
+#803=ORIENTED_EDGE('',*,*,#558,.F.);
+#804=ORIENTED_EDGE('',*,*,#581,.F.);
+#805=ORIENTED_EDGE('',*,*,#582,.F.);
+#806=ORIENTED_EDGE('',*,*,#533,.F.);
+#807=ORIENTED_EDGE('',*,*,#583,.T.);
+#808=ORIENTED_EDGE('',*,*,#584,.F.);
+#809=ORIENTED_EDGE('',*,*,#583,.F.);
+#810=ORIENTED_EDGE('',*,*,#536,.F.);
+#811=ORIENTED_EDGE('',*,*,#585,.T.);
+#812=ORIENTED_EDGE('',*,*,#586,.F.);
+#813=ORIENTED_EDGE('',*,*,#585,.F.);
+#814=ORIENTED_EDGE('',*,*,#535,.F.);
+#815=ORIENTED_EDGE('',*,*,#587,.T.);
+#816=ORIENTED_EDGE('',*,*,#588,.F.);
+#817=ORIENTED_EDGE('',*,*,#587,.F.);
+#818=ORIENTED_EDGE('',*,*,#534,.F.);
+#819=ORIENTED_EDGE('',*,*,#582,.T.);
+#820=ORIENTED_EDGE('',*,*,#515,.F.);
+#821=ORIENTED_EDGE('',*,*,#521,.F.);
+#822=ORIENTED_EDGE('',*,*,#468,.F.);
+#823=ORIENTED_EDGE('',*,*,#532,.F.);
+#824=ORIENTED_EDGE('',*,*,#476,.F.);
+#825=ORIENTED_EDGE('',*,*,#516,.F.);
+#826=ORIENTED_EDGE('',*,*,#589,.T.);
+#827=ORIENTED_EDGE('',*,*,#590,.T.);
+#828=ORIENTED_EDGE('',*,*,#576,.F.);
+#829=ORIENTED_EDGE('',*,*,#591,.T.);
+#830=ORIENTED_EDGE('',*,*,#579,.F.);
+#831=ORIENTED_EDGE('',*,*,#591,.F.);
+#832=ORIENTED_EDGE('',*,*,#575,.F.);
+#833=ORIENTED_EDGE('',*,*,#592,.T.);
+#834=ORIENTED_EDGE('',*,*,#589,.F.);
+#835=ORIENTED_EDGE('',*,*,#590,.F.);
+#836=ORIENTED_EDGE('',*,*,#592,.F.);
+#837=ORIENTED_EDGE('',*,*,#512,.F.);
+#838=ORIENTED_EDGE('',*,*,#574,.T.);
+#839=ORIENTED_EDGE('',*,*,#522,.F.);
+#840=ORIENTED_EDGE('',*,*,#517,.F.);
+#841=ORIENTED_EDGE('',*,*,#555,.F.);
+#842=ORIENTED_EDGE('',*,*,#571,.T.);
+#843=ORIENTED_EDGE('',*,*,#519,.T.);
+#844=ORIENTED_EDGE('',*,*,#530,.F.);
+#845=ORIENTED_EDGE('',*,*,#563,.F.);
+#846=ORIENTED_EDGE('',*,*,#560,.F.);
+#847=ORIENTED_EDGE('',*,*,#581,.T.);
+#848=ORIENTED_EDGE('',*,*,#584,.T.);
+#849=ORIENTED_EDGE('',*,*,#586,.T.);
+#850=ORIENTED_EDGE('',*,*,#588,.T.);
+#851=SPHERICAL_SURFACE('',#930,2.);
+#852=SPHERICAL_SURFACE('',#944,2.);
+#853=SPHERICAL_SURFACE('',#955,2.);
+#854=ADVANCED_FACE('',(#239),#851,.T.);
+#855=ADVANCED_FACE('',(#240),#211,.T.);
+#856=ADVANCED_FACE('',(#241),#38,.T.);
+#857=ADVANCED_FACE('',(#242),#212,.T.);
+#858=ADVANCED_FACE('',(#243),#852,.T.);
+#859=ADVANCED_FACE('',(#244),#39,.T.);
+#860=ADVANCED_FACE('',(#245),#213,.T.);
+#861=ADVANCED_FACE('',(#246),#853,.T.);
+#862=ADVANCED_FACE('',(#247),#214,.T.);
+#863=ADVANCED_FACE('',(#248),#215,.T.);
+#864=ADVANCED_FACE('',(#249),#216,.T.);
+#865=ADVANCED_FACE('',(#250),#217,.T.);
+#866=ADVANCED_FACE('',(#251),#218,.F.);
+#867=ADVANCED_FACE('',(#252),#219,.T.);
+#868=ADVANCED_FACE('',(#253),#220,.T.);
+#869=ADVANCED_FACE('',(#254),#221,.T.);
+#870=ADVANCED_FACE('',(#255),#222,.T.);
+#871=ADVANCED_FACE('',(#256),#223,.T.);
+#872=ADVANCED_FACE('',(#257),#224,.T.);
+#873=ADVANCED_FACE('',(#258),#20,.T.);
+#874=ADVANCED_FACE('',(#259),#21,.T.);
+#875=ADVANCED_FACE('',(#260),#22,.T.);
+#876=ADVANCED_FACE('',(#261),#23,.T.);
+#877=ADVANCED_FACE('',(#262,#15),#24,.T.);
+#878=ADVANCED_FACE('',(#263),#25,.T.);
+#879=ADVANCED_FACE('',(#264),#40,.T.);
+#880=ADVANCED_FACE('',(#265),#225,.T.);
+#881=ADVANCED_FACE('',(#266),#41,.T.);
+#882=ADVANCED_FACE('',(#267),#226,.T.);
+#883=ADVANCED_FACE('',(#268),#227,.T.);
+#884=ADVANCED_FACE('',(#269),#228,.T.);
+#885=ADVANCED_FACE('',(#270),#229,.F.);
+#886=ADVANCED_FACE('',(#271),#230,.T.);
+#887=ADVANCED_FACE('',(#272),#231,.T.);
+#888=ADVANCED_FACE('',(#273),#232,.T.);
+#889=ADVANCED_FACE('',(#274),#233,.T.);
+#890=ADVANCED_FACE('',(#275),#234,.T.);
+#891=ADVANCED_FACE('',(#276),#26,.F.);
+#892=ADVANCED_FACE('',(#277,#16,#17),#27,.T.);
+#893=ADVANCED_FACE('',(#278),#28,.T.);
+#894=ADVANCED_FACE('',(#279,#18),#29,.T.);
+#895=ADVANCED_FACE('',(#280),#30,.T.);
+#896=ADVANCED_FACE('',(#281),#31,.T.);
+#897=ADVANCED_FACE('',(#282),#32,.T.);
+#898=ADVANCED_FACE('',(#283),#33,.F.);
+#899=ADVANCED_FACE('',(#284),#235,.F.);
+#900=ADVANCED_FACE('',(#285),#34,.F.);
+#901=ADVANCED_FACE('',(#286),#236,.F.);
+#902=ADVANCED_FACE('',(#287),#35,.T.);
+#903=ADVANCED_FACE('',(#288),#237,.F.);
+#904=ADVANCED_FACE('',(#289),#238,.F.);
+#905=ADVANCED_FACE('',(#290),#36,.T.);
+#906=ADVANCED_FACE('',(#291,#19),#37,.T.);
+#907=CLOSED_SHELL('',(#854,#855,#856,#857,#858,#859,#860,#861,#862,#863,
+#864,#865,#866,#867,#868,#869,#870,#871,#872,#873,#874,#875,#876,#877,#878,
+#879,#880,#881,#882,#883,#884,#885,#886,#887,#888,#889,#890,#891,#892,#893,
+#894,#895,#896,#897,#898,#899,#900,#901,#902,#903,#904,#905,#906));
+#908=DERIVED_UNIT_ELEMENT(#911,1.);
+#909=DERIVED_UNIT_ELEMENT(#1589,-3.);
+#910=DIMENSIONAL_EXPONENTS(0.,1.,0.,0.,0.,0.,0.);
+#911=(
+CONVERSION_BASED_UNIT('gram',#913)
+MASS_UNIT()
+NAMED_UNIT(#910)
+);
+#912=(
+MASS_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.KILO.,.GRAM.)
+);
+#913=MASS_MEASURE_WITH_UNIT(MASS_MEASURE(0.001),#912);
+#914=DERIVED_UNIT((#908,#909));
+#915=MEASURE_REPRESENTATION_ITEM('density measure',
+POSITIVE_RATIO_MEASURE(1.),#914);
+#916=PROPERTY_DEFINITION_REPRESENTATION(#921,#918);
+#917=PROPERTY_DEFINITION_REPRESENTATION(#922,#919);
+#918=REPRESENTATION('material name',(#920),#1586);
+#919=REPRESENTATION('density',(#915),#1586);
+#920=DESCRIPTIVE_REPRESENTATION_ITEM('Generisch','Generisch');
+#921=PROPERTY_DEFINITION('material property','material name',#1596);
+#922=PROPERTY_DEFINITION('material property','density of part',#1596);
+#923=DATE_TIME_ROLE('creation_date');
+#924=APPLIED_DATE_AND_TIME_ASSIGNMENT(#925,#923,(#1596));
+#925=DATE_AND_TIME(#926,#927);
+#926=CALENDAR_DATE(2025,7,1);
+#927=LOCAL_TIME(0,0,0.,#928);
+#928=COORDINATED_UNIVERSAL_TIME_OFFSET(0,0,.BEHIND.);
+#929=AXIS2_PLACEMENT_3D('',#1324,#1035,#1036);
+#930=AXIS2_PLACEMENT_3D('',#1325,#1037,#1038);
+#931=AXIS2_PLACEMENT_3D('',#1328,#1039,#1040);
+#932=AXIS2_PLACEMENT_3D('',#1330,#1041,#1042);
+#933=AXIS2_PLACEMENT_3D('',#1331,#1043,#1044);
+#934=AXIS2_PLACEMENT_3D('',#1332,#1045,#1046);
+#935=AXIS2_PLACEMENT_3D('',#1337,#1048,#1049);
+#936=AXIS2_PLACEMENT_3D('',#1340,#1051,#1052);
+#937=AXIS2_PLACEMENT_3D('',#1341,#1053,#1054);
+#938=AXIS2_PLACEMENT_3D('',#1344,#1055,#1056);
+#939=AXIS2_PLACEMENT_3D('',#1346,#1057,#1058);
+#940=AXIS2_PLACEMENT_3D('',#1348,#1059,#1060);
+#941=AXIS2_PLACEMENT_3D('',#1349,#1061,#1062);
+#942=AXIS2_PLACEMENT_3D('',#1350,#1063,#1064);
+#943=AXIS2_PLACEMENT_3D('',#1355,#1067,#1068);
+#944=AXIS2_PLACEMENT_3D('',#1356,#1069,#1070);
+#945=AXIS2_PLACEMENT_3D('',#1359,#1071,#1072);
+#946=AXIS2_PLACEMENT_3D('',#1361,#1073,#1074);
+#947=AXIS2_PLACEMENT_3D('',#1362,#1075,#1076);
+#948=AXIS2_PLACEMENT_3D('',#1363,#1077,#1078);
+#949=AXIS2_PLACEMENT_3D('',#1366,#1079,#1080);
+#950=AXIS2_PLACEMENT_3D('',#1368,#1081,#1082);
+#951=AXIS2_PLACEMENT_3D('',#1370,#1083,#1084);
+#952=AXIS2_PLACEMENT_3D('',#1371,#1085,#1086);
+#953=AXIS2_PLACEMENT_3D('',#1372,#1087,#1088);
+#954=AXIS2_PLACEMENT_3D('',#1377,#1091,#1092);
+#955=AXIS2_PLACEMENT_3D('',#1378,#1093,#1094);
+#956=AXIS2_PLACEMENT_3D('',#1381,#1095,#1096);
+#957=AXIS2_PLACEMENT_3D('',#1383,#1097,#1098);
+#958=AXIS2_PLACEMENT_3D('',#1384,#1099,#1100);
+#959=AXIS2_PLACEMENT_3D('',#1385,#1101,#1102);
+#960=AXIS2_PLACEMENT_3D('',#1388,#1105,#1106);
+#961=AXIS2_PLACEMENT_3D('',#1393,#1109,#1110);
+#962=AXIS2_PLACEMENT_3D('',#1394,#1111,#1112);
+#963=AXIS2_PLACEMENT_3D('',#1397,#1115,#1116);
+#964=AXIS2_PLACEMENT_3D('',#1400,#1119,#1120);
+#965=AXIS2_PLACEMENT_3D('',#1403,#1123,#1124);
+#966=AXIS2_PLACEMENT_3D('',#1406,#1127,#1128);
+#967=AXIS2_PLACEMENT_3D('',#1409,#1131,#1132);
+#968=AXIS2_PLACEMENT_3D('',#1414,#1135,#1136);
+#969=AXIS2_PLACEMENT_3D('',#1415,#1137,#1138);
+#970=AXIS2_PLACEMENT_3D('',#1418,#1141,#1142);
+#971=AXIS2_PLACEMENT_3D('',#1421,#1143,#1144);
+#972=AXIS2_PLACEMENT_3D('',#1424,#1147,#1148);
+#973=AXIS2_PLACEMENT_3D('',#1427,#1149,#1150);
+#974=AXIS2_PLACEMENT_3D('',#1432,#1154,#1155);
+#975=AXIS2_PLACEMENT_3D('',#1438,#1159,#1160);
+#976=AXIS2_PLACEMENT_3D('',#1453,#1168,#1169);
+#977=AXIS2_PLACEMENT_3D('',#1457,#1172,#1173);
+#978=AXIS2_PLACEMENT_3D('',#1459,#1175,#1176);
+#979=AXIS2_PLACEMENT_3D('',#1461,#1178,#1179);
+#980=AXIS2_PLACEMENT_3D('',#1466,#1181,#1182);
+#981=AXIS2_PLACEMENT_3D('',#1469,#1184,#1185);
+#982=AXIS2_PLACEMENT_3D('',#1470,#1186,#1187);
+#983=AXIS2_PLACEMENT_3D('',#1471,#1188,#1189);
+#984=AXIS2_PLACEMENT_3D('',#1473,#1190,#1191);
+#985=AXIS2_PLACEMENT_3D('',#1475,#1192,#1193);
+#986=AXIS2_PLACEMENT_3D('',#1476,#1194,#1195);
+#987=AXIS2_PLACEMENT_3D('',#1477,#1196,#1197);
+#988=AXIS2_PLACEMENT_3D('',#1482,#1199,#1200);
+#989=AXIS2_PLACEMENT_3D('',#1485,#1202,#1203);
+#990=AXIS2_PLACEMENT_3D('',#1486,#1204,#1205);
+#991=AXIS2_PLACEMENT_3D('',#1489,#1206,#1207);
+#992=AXIS2_PLACEMENT_3D('',#1491,#1208,#1209);
+#993=AXIS2_PLACEMENT_3D('',#1493,#1210,#1211);
+#994=AXIS2_PLACEMENT_3D('',#1494,#1212,#1213);
+#995=AXIS2_PLACEMENT_3D('',#1495,#1214,#1215);
+#996=AXIS2_PLACEMENT_3D('',#1500,#1218,#1219);
+#997=AXIS2_PLACEMENT_3D('',#1501,#1220,#1221);
+#998=AXIS2_PLACEMENT_3D('',#1504,#1224,#1225);
+#999=AXIS2_PLACEMENT_3D('',#1510,#1228,#1229);
+#1000=AXIS2_PLACEMENT_3D('',#1511,#1230,#1231);
+#1001=AXIS2_PLACEMENT_3D('',#1512,#1232,#1233);
+#1002=AXIS2_PLACEMENT_3D('',#1515,#1236,#1237);
+#1003=AXIS2_PLACEMENT_3D('',#1520,#1240,#1241);
+#1004=AXIS2_PLACEMENT_3D('',#1521,#1242,#1243);
+#1005=AXIS2_PLACEMENT_3D('',#1523,#1245,#1246);
+#1006=AXIS2_PLACEMENT_3D('',#1524,#1247,#1248);
+#1007=AXIS2_PLACEMENT_3D('',#1527,#1250,#1251);
+#1008=AXIS2_PLACEMENT_3D('',#1528,#1252,#1253);
+#1009=AXIS2_PLACEMENT_3D('',#1532,#1255,#1256);
+#1010=AXIS2_PLACEMENT_3D('',#1534,#1258,#1259);
+#1011=AXIS2_PLACEMENT_3D('',#1536,#1260,#1261);
+#1012=AXIS2_PLACEMENT_3D('',#1538,#1263,#1264);
+#1013=AXIS2_PLACEMENT_3D('',#1541,#1267,#1268);
+#1014=AXIS2_PLACEMENT_3D('',#1545,#1271,#1272);
+#1015=AXIS2_PLACEMENT_3D('',#1547,#1273,#1274);
+#1016=AXIS2_PLACEMENT_3D('',#1548,#1275,#1276);
+#1017=AXIS2_PLACEMENT_3D('',#1550,#1278,#1279);
+#1018=AXIS2_PLACEMENT_3D('',#1553,#1281,#1282);
+#1019=AXIS2_PLACEMENT_3D('',#1554,#1283,#1284);
+#1020=AXIS2_PLACEMENT_3D('',#1556,#1286,#1287);
+#1021=AXIS2_PLACEMENT_3D('',#1557,#1288,#1289);
+#1022=AXIS2_PLACEMENT_3D('',#1558,#1290,#1291);
+#1023=AXIS2_PLACEMENT_3D('',#1564,#1295,#1296);
+#1024=AXIS2_PLACEMENT_3D('',#1566,#1297,#1298);
+#1025=AXIS2_PLACEMENT_3D('',#1568,#1300,#1301);
+#1026=AXIS2_PLACEMENT_3D('',#1572,#1304,#1305);
+#1027=AXIS2_PLACEMENT_3D('',#1573,#1306,#1307);
+#1028=AXIS2_PLACEMENT_3D('',#1574,#1308,#1309);
+#1029=AXIS2_PLACEMENT_3D('',#1576,#1310,#1311);
+#1030=AXIS2_PLACEMENT_3D('',#1577,#1312,#1313);
+#1031=AXIS2_PLACEMENT_3D('',#1578,#1314,#1315);
+#1032=AXIS2_PLACEMENT_3D('',#1580,#1317,#1318);
+#1033=AXIS2_PLACEMENT_3D('',#1582,#1320,#1321);
+#1034=AXIS2_PLACEMENT_3D('',#1583,#1322,#1323);
+#1035=DIRECTION('axis',(0.,0.,1.));
+#1036=DIRECTION('refdir',(1.,0.,0.));
+#1037=DIRECTION('center_axis',(-0.816496580927728,0.408248290463863,-0.408248290463858));
+#1038=DIRECTION('ref_axis',(-0.577350269189624,-0.57735026918963,0.577350269189624));
+#1039=DIRECTION('center_axis',(-1.,0.,0.));
+#1040=DIRECTION('ref_axis',(0.,0.,1.));
+#1041=DIRECTION('center_axis',(0.,-1.,-4.44089209850062E-15));
+#1042=DIRECTION('ref_axis',(-1.,0.,0.));
+#1043=DIRECTION('center_axis',(0.,-2.22044604925031E-15,1.));
+#1044=DIRECTION('ref_axis',(0.,-1.,-2.22044604925031E-15));
+#1045=DIRECTION('center_axis',(0.,0.707106781186548,0.707106781186547));
+#1046=DIRECTION('ref_axis',(0.707106781186547,-0.499999999999999,0.500000000000001));
+#1047=DIRECTION('',(0.,-0.707106781186548,-0.707106781186547));
+#1048=DIRECTION('center_axis',(0.,2.01858731750028E-16,-1.));
+#1049=DIRECTION('ref_axis',(-4.90653893338679E-17,-1.,-1.38777878078144E-16));
+#1050=DIRECTION('',(0.,0.707106781186548,0.707106781186547));
+#1051=DIRECTION('center_axis',(0.,-0.382683432365088,-0.923879532511287));
+#1052=DIRECTION('ref_axis',(0.,-0.923879532511287,0.382683432365088));
+#1053=DIRECTION('center_axis',(-1.,0.,0.));
+#1054=DIRECTION('ref_axis',(0.,0.,1.));
+#1055=DIRECTION('center_axis',(0.,0.,1.));
+#1056=DIRECTION('ref_axis',(0.,-1.,0.));
+#1057=DIRECTION('center_axis',(-1.,0.,0.));
+#1058=DIRECTION('ref_axis',(0.,0.630592625094466,-0.776114000116266));
+#1059=DIRECTION('center_axis',(0.,-0.776114000116266,-0.630592625094466));
+#1060=DIRECTION('ref_axis',(1.,0.,0.));
+#1061=DIRECTION('center_axis',(1.,0.,0.));
+#1062=DIRECTION('ref_axis',(0.,0.902937601690855,-0.429771668974081));
+#1063=DIRECTION('center_axis',(0.,-1.,-2.01858731750028E-16));
+#1064=DIRECTION('ref_axis',(-0.707106781186547,0.,0.707106781186548));
+#1065=DIRECTION('',(0.,-1.,-2.01858731750028E-16));
+#1066=DIRECTION('',(0.,1.,2.01858731750028E-16));
+#1067=DIRECTION('center_axis',(-8.49727915508614E-16,-0.923879532511287,
+-0.38268343236509));
+#1068=DIRECTION('ref_axis',(-2.05142465794791E-15,0.38268343236509,-0.923879532511287));
+#1069=DIRECTION('center_axis',(0.,0.,1.));
+#1070=DIRECTION('ref_axis',(1.,0.,0.));
+#1071=DIRECTION('center_axis',(0.,-0.776114000116266,-0.630592625094466));
+#1072=DIRECTION('ref_axis',(0.,-0.630592625094466,0.776114000116266));
+#1073=DIRECTION('center_axis',(1.,0.,0.));
+#1074=DIRECTION('ref_axis',(0.,-1.,0.));
+#1075=DIRECTION('center_axis',(0.,3.33066907387547E-15,1.));
+#1076=DIRECTION('ref_axis',(1.,0.,0.));
+#1077=DIRECTION('center_axis',(1.,0.,0.));
+#1078=DIRECTION('ref_axis',(0.,0.,-1.));
+#1079=DIRECTION('center_axis',(1.,0.,0.));
+#1080=DIRECTION('ref_axis',(0.,1.,0.));
+#1081=DIRECTION('center_axis',(0.,0.,1.));
+#1082=DIRECTION('ref_axis',(-1.,0.,0.));
+#1083=DIRECTION('center_axis',(-1.,0.,0.));
+#1084=DIRECTION('ref_axis',(0.,0.902937601690855,-0.429771668974081));
+#1085=DIRECTION('center_axis',(0.,-0.776114000116267,-0.630592625094464));
+#1086=DIRECTION('ref_axis',(0.,-0.630592625094464,0.776114000116267));
+#1087=DIRECTION('center_axis',(0.,0.,-1.));
+#1088=DIRECTION('ref_axis',(-0.707106781186549,-0.707106781186546,0.));
+#1089=DIRECTION('',(0.,0.,-1.));
+#1090=DIRECTION('',(0.,0.,1.));
+#1091=DIRECTION('center_axis',(-0.707106781186546,0.,-0.707106781186549));
+#1092=DIRECTION('ref_axis',(-0.707106781186549,0.,0.707106781186546));
+#1093=DIRECTION('center_axis',(0.,0.,1.));
+#1094=DIRECTION('ref_axis',(1.,0.,0.));
+#1095=DIRECTION('center_axis',(-1.,0.,0.));
+#1096=DIRECTION('ref_axis',(0.,-0.630592625094467,0.776114000116265));
+#1097=DIRECTION('center_axis',(0.,-0.776114000116262,-0.63059262509447));
+#1098=DIRECTION('ref_axis',(-1.,0.,0.));
+#1099=DIRECTION('center_axis',(4.44089209850063E-15,0.,1.));
+#1100=DIRECTION('ref_axis',(0.,-1.,0.));
+#1101=DIRECTION('center_axis',(0.,-0.776114000116265,-0.630592625094466));
+#1102=DIRECTION('ref_axis',(-0.707106781186548,-0.445896321370521,0.548795472456029));
+#1103=DIRECTION('',(0.,0.776114000116265,0.630592625094466));
+#1104=DIRECTION('',(0.,-0.776114000116265,-0.630592625094466));
+#1105=DIRECTION('center_axis',(0.,0.,-1.));
+#1106=DIRECTION('ref_axis',(-0.707106781186547,-0.707106781186548,0.));
+#1107=DIRECTION('',(0.,0.,1.));
+#1108=DIRECTION('',(0.,0.,-1.));
+#1109=DIRECTION('center_axis',(5.80230514691305E-15,0.38268343236509,0.923879532511287));
+#1110=DIRECTION('ref_axis',(-1.40080037787047E-14,-0.923879532511287,0.38268343236509));
+#1111=DIRECTION('center_axis',(1.,0.,0.));
+#1112=DIRECTION('ref_axis',(0.,-0.902937601690855,0.429771668974082));
+#1113=DIRECTION('',(-1.,0.,0.));
+#1114=DIRECTION('',(1.,0.,0.));
+#1115=DIRECTION('center_axis',(0.,-0.707106781186548,-0.707106781186547));
+#1116=DIRECTION('ref_axis',(-0.707106781186547,-0.5,0.500000000000001));
+#1117=DIRECTION('',(0.,0.707106781186548,0.707106781186547));
+#1118=DIRECTION('',(0.,-0.707106781186548,-0.707106781186547));
+#1119=DIRECTION('center_axis',(1.,0.,0.));
+#1120=DIRECTION('ref_axis',(0.,0.902937601690855,-0.429771668974081));
+#1121=DIRECTION('',(-1.,0.,0.));
+#1122=DIRECTION('',(1.,0.,0.));
+#1123=DIRECTION('center_axis',(0.,0.,-1.));
+#1124=DIRECTION('ref_axis',(0.707106781186547,-0.707106781186548,0.));
+#1125=DIRECTION('',(0.,0.,1.));
+#1126=DIRECTION('',(0.,0.,-1.));
+#1127=DIRECTION('center_axis',(0.,-0.776114000116265,-0.630592625094466));
+#1128=DIRECTION('ref_axis',(0.707106781186547,-0.445896321370523,0.548795472456029));
+#1129=DIRECTION('',(0.,0.776114000116265,0.630592625094466));
+#1130=DIRECTION('',(0.,-0.776114000116265,-0.630592625094466));
+#1131=DIRECTION('center_axis',(1.,0.,0.));
+#1132=DIRECTION('ref_axis',(0.,-0.707106781186548,0.707106781186548));
+#1133=DIRECTION('',(-1.,0.,0.));
+#1134=DIRECTION('',(1.,0.,0.));
+#1135=DIRECTION('center_axis',(-0.707106781186546,0.,0.707106781186549));
+#1136=DIRECTION('ref_axis',(-0.707106781186549,0.,-0.707106781186546));
+#1137=DIRECTION('center_axis',(0.,0.,-1.));
+#1138=DIRECTION('ref_axis',(0.707106781186548,-0.707106781186547,0.));
+#1139=DIRECTION('',(0.,0.,-1.));
+#1140=DIRECTION('',(0.,0.,1.));
+#1141=DIRECTION('center_axis',(0.,1.77635683940025E-15,-1.));
+#1142=DIRECTION('ref_axis',(-0.707106781186546,-0.707106781186549,-3.14018491736754E-15));
+#1143=DIRECTION('center_axis',(0.,-1.38777878078145E-16,1.));
+#1144=DIRECTION('ref_axis',(-0.707106781186546,-0.707106781186549,-3.14018491736754E-15));
+#1145=DIRECTION('',(0.,-1.77635683940025E-15,1.));
+#1146=DIRECTION('',(0.,1.77635683940025E-15,-1.));
+#1147=DIRECTION('center_axis',(1.,0.,0.));
+#1148=DIRECTION('ref_axis',(0.,-0.70710678118655,0.707106781186545));
+#1149=DIRECTION('center_axis',(-1.,0.,0.));
+#1150=DIRECTION('ref_axis',(0.,-0.70710678118655,0.707106781186545));
+#1151=DIRECTION('',(-1.,0.,0.));
+#1152=DIRECTION('',(-1.,0.,0.));
+#1153=DIRECTION('',(1.,0.,0.));
+#1154=DIRECTION('center_axis',(0.,-1.77635683940025E-15,1.));
+#1155=DIRECTION('ref_axis',(0.,-1.,-1.77635683940025E-15));
+#1156=DIRECTION('',(0.,-1.,-1.77635683940025E-15));
+#1157=DIRECTION('',(1.,0.,0.));
+#1158=DIRECTION('',(0.,-1.,-1.77635683940025E-15));
+#1159=DIRECTION('center_axis',(1.,0.,0.));
+#1160=DIRECTION('ref_axis',(0.,0.,-1.));
+#1161=DIRECTION('',(0.,-1.,-2.01858731750028E-16));
+#1162=DIRECTION('',(0.,1.77635683940025E-15,-1.));
+#1163=DIRECTION('',(0.,1.,1.38777878078145E-16));
+#1164=DIRECTION('',(0.,-4.44089209850063E-16,1.));
+#1165=DIRECTION('',(0.,-1.,-4.03717463500057E-16));
+#1166=DIRECTION('',(0.,0.707106781186548,-0.707106781186547));
+#1167=DIRECTION('',(0.,0.,-1.));
+#1168=DIRECTION('center_axis',(1.,0.,0.));
+#1169=DIRECTION('ref_axis',(0.,-0.902937601690855,0.429771668974081));
+#1170=DIRECTION('',(0.,-0.776114000116265,-0.630592625094466));
+#1171=DIRECTION('',(0.,-2.22044604925031E-16,1.));
+#1172=DIRECTION('center_axis',(0.,-1.,0.));
+#1173=DIRECTION('ref_axis',(0.,0.,-1.));
+#1174=DIRECTION('',(-1.,0.,0.));
+#1175=DIRECTION('center_axis',(0.,-0.707106781186547,0.707106781186548));
+#1176=DIRECTION('ref_axis',(1.,0.,0.));
+#1177=DIRECTION('',(1.,0.,0.));
+#1178=DIRECTION('center_axis',(0.,-1.,0.));
+#1179=DIRECTION('ref_axis',(0.,0.,-1.));
+#1180=DIRECTION('',(-1.48029736616688E-16,0.,-1.));
+#1181=DIRECTION('center_axis',(0.,1.,0.));
+#1182=DIRECTION('ref_axis',(-1.,0.,0.));
+#1183=DIRECTION('',(-1.48029736616688E-16,0.,1.));
+#1184=DIRECTION('center_axis',(0.,1.,0.));
+#1185=DIRECTION('ref_axis',(1.,0.,0.));
+#1186=DIRECTION('center_axis',(0.,-0.630592625094466,0.776114000116265));
+#1187=DIRECTION('ref_axis',(0.,-0.776114000116265,-0.630592625094466));
+#1188=DIRECTION('center_axis',(-1.,0.,0.));
+#1189=DIRECTION('ref_axis',(0.,0.,1.));
+#1190=DIRECTION('center_axis',(0.,0.,-1.));
+#1191=DIRECTION('ref_axis',(0.,1.,0.));
+#1192=DIRECTION('center_axis',(-1.,0.,0.));
+#1193=DIRECTION('ref_axis',(0.,-0.630592625094466,0.776114000116266));
+#1194=DIRECTION('center_axis',(0.,0.776114000116262,0.63059262509447));
+#1195=DIRECTION('ref_axis',(1.,0.,0.));
+#1196=DIRECTION('center_axis',(0.,-1.,-4.03717463500057E-16));
+#1197=DIRECTION('ref_axis',(-0.707106781186548,0.,0.707106781186547));
+#1198=DIRECTION('',(0.,-1.,-4.03717463500057E-16));
+#1199=DIRECTION('center_axis',(4.24863957754315E-16,0.923879532511283,-0.382683432365098));
+#1200=DIRECTION('ref_axis',(-1.02571232897395E-15,0.382683432365098,0.923879532511284));
+#1201=DIRECTION('',(0.,1.,4.03717463500057E-16));
+#1202=DIRECTION('center_axis',(0.,-0.707106781186547,0.707106781186548));
+#1203=DIRECTION('ref_axis',(0.,0.707106781186548,0.707106781186547));
+#1204=DIRECTION('center_axis',(1.,7.14706072102445E-15,0.));
+#1205=DIRECTION('ref_axis',(0.,0.,-1.));
+#1206=DIRECTION('center_axis',(1.,0.,0.));
+#1207=DIRECTION('ref_axis',(0.,-1.,0.));
+#1208=DIRECTION('center_axis',(0.,0.,-1.));
+#1209=DIRECTION('ref_axis',(-1.,0.,0.));
+#1210=DIRECTION('center_axis',(-1.,0.,0.));
+#1211=DIRECTION('ref_axis',(0.,-0.902937601690854,0.429771668974082));
+#1212=DIRECTION('center_axis',(-5.54693388526812E-15,0.776114000116266,
+0.630592625094466));
+#1213=DIRECTION('ref_axis',(0.,0.630592625094466,-0.776114000116266));
+#1214=DIRECTION('center_axis',(0.,0.,1.));
+#1215=DIRECTION('ref_axis',(-0.707106781186547,0.707106781186548,0.));
+#1216=DIRECTION('',(0.,0.,1.));
+#1217=DIRECTION('',(0.,0.,-1.));
+#1218=DIRECTION('center_axis',(-1.53856849346093E-15,-0.382683432365096,
+0.923879532511284));
+#1219=DIRECTION('ref_axis',(-3.71443292355325E-15,-0.923879532511284,-0.382683432365096));
+#1220=DIRECTION('center_axis',(0.,-0.707106781186548,0.707106781186547));
+#1221=DIRECTION('ref_axis',(-0.707106781186545,0.500000000000001,0.500000000000003));
+#1222=DIRECTION('',(0.,-0.707106781186548,0.707106781186547));
+#1223=DIRECTION('',(0.,0.707106781186548,-0.707106781186547));
+#1224=DIRECTION('center_axis',(0.,0.776114000116266,0.630592625094466));
+#1225=DIRECTION('ref_axis',(-0.707106781186547,0.445896321370523,-0.548795472456028));
+#1226=DIRECTION('',(0.,-0.776114000116265,-0.630592625094466));
+#1227=DIRECTION('',(0.,0.776114000116265,0.630592625094466));
+#1228=DIRECTION('center_axis',(0.,-1.,-2.22044604925031E-16));
+#1229=DIRECTION('ref_axis',(1.61561181124314E-16,2.28482013499021E-16,-1.));
+#1230=DIRECTION('center_axis',(-0.707106781186545,-0.548795472456033,-0.445896321370521));
+#1231=DIRECTION('ref_axis',(0.70710678118655,-0.548795472456024,-0.445896321370525));
+#1232=DIRECTION('center_axis',(1.,0.,0.));
+#1233=DIRECTION('ref_axis',(0.,-0.902937601690855,0.429771668974081));
+#1234=DIRECTION('',(-1.,0.,0.));
+#1235=DIRECTION('',(1.,0.,0.));
+#1236=DIRECTION('center_axis',(1.,0.,0.));
+#1237=DIRECTION('ref_axis',(0.,0.902937601690854,-0.429771668974083));
+#1238=DIRECTION('',(-1.,0.,0.));
+#1239=DIRECTION('',(1.,0.,0.));
+#1240=DIRECTION('center_axis',(-0.707106781186545,0.548795472456033,0.445896321370521));
+#1241=DIRECTION('ref_axis',(-0.70710678118655,-0.548795472456029,-0.445896321370518));
+#1242=DIRECTION('center_axis',(0.,0.776114000116266,0.630592625094466));
+#1243=DIRECTION('ref_axis',(0.707106781186548,0.445896321370524,-0.548795472456027));
+#1244=DIRECTION('',(0.,0.776114000116265,0.630592625094466));
+#1245=DIRECTION('center_axis',(0.,-1.,-2.22044604925031E-16));
+#1246=DIRECTION('ref_axis',(-1.07707454082876E-16,2.28482013499021E-16,
+-1.));
+#1247=DIRECTION('center_axis',(0.,0.,1.));
+#1248=DIRECTION('ref_axis',(0.707106781186547,0.707106781186548,0.));
+#1249=DIRECTION('',(0.,0.,1.));
+#1250=DIRECTION('center_axis',(1.53856849346093E-15,-0.382683432365093,
+0.923879532511286));
+#1251=DIRECTION('ref_axis',(3.71443292355329E-15,-0.923879532511286,-0.382683432365093));
+#1252=DIRECTION('center_axis',(0.,-4.44089209850063E-16,1.));
+#1253=DIRECTION('ref_axis',(-0.707106781186547,0.707106781186548,0.));
+#1254=DIRECTION('',(0.,4.44089209850063E-16,-1.));
+#1255=DIRECTION('center_axis',(0.,-1.38777878078145E-16,1.));
+#1256=DIRECTION('ref_axis',(-0.707106781186547,0.707106781186548,0.));
+#1257=DIRECTION('',(0.,-4.44089209850063E-16,1.));
+#1258=DIRECTION('center_axis',(0.,0.707106781186548,-0.707106781186547));
+#1259=DIRECTION('ref_axis',(0.707106781186545,0.500000000000001,0.500000000000002));
+#1260=DIRECTION('center_axis',(0.,4.03717463500057E-16,-1.));
+#1261=DIRECTION('ref_axis',(-1.96261557335472E-16,1.,4.16333634234434E-16));
+#1262=DIRECTION('',(0.,-0.707106781186548,0.707106781186547));
+#1263=DIRECTION('center_axis',(1.,0.,0.));
+#1264=DIRECTION('ref_axis',(0.,0.,-1.));
+#1265=DIRECTION('',(0.,-2.22044604925031E-16,1.));
+#1266=DIRECTION('',(0.,1.,1.38777878078145E-16));
+#1267=DIRECTION('center_axis',(0.,1.38777878078145E-16,-1.));
+#1268=DIRECTION('ref_axis',(0.,1.,1.38777878078145E-16));
+#1269=DIRECTION('',(1.,0.,0.));
+#1270=DIRECTION('',(1.,0.,0.));
+#1271=DIRECTION('center_axis',(0.,-1.38777878078145E-16,1.));
+#1272=DIRECTION('ref_axis',(-1.,0.,0.));
+#1273=DIRECTION('center_axis',(0.,-1.38777878078145E-16,1.));
+#1274=DIRECTION('ref_axis',(-1.,0.,0.));
+#1275=DIRECTION('center_axis',(0.,1.,4.44089209850063E-16));
+#1276=DIRECTION('ref_axis',(0.,-4.44089209850063E-16,1.));
+#1277=DIRECTION('',(1.,0.,0.));
+#1278=DIRECTION('center_axis',(0.,-4.03717463500057E-16,1.));
+#1279=DIRECTION('ref_axis',(0.,-1.,-4.03717463500057E-16));
+#1280=DIRECTION('',(-1.,0.,0.));
+#1281=DIRECTION('center_axis',(0.,4.03717463500057E-16,-1.));
+#1282=DIRECTION('ref_axis',(-1.,0.,0.));
+#1283=DIRECTION('center_axis',(0.,1.,0.));
+#1284=DIRECTION('ref_axis',(0.,0.,1.));
+#1285=DIRECTION('',(1.,0.,0.));
+#1286=DIRECTION('center_axis',(0.,0.707106781186547,0.707106781186548));
+#1287=DIRECTION('ref_axis',(1.,0.,0.));
+#1288=DIRECTION('center_axis',(0.,0.630592625094466,-0.776114000116266));
+#1289=DIRECTION('ref_axis',(0.,0.776114000116265,0.630592625094466));
+#1290=DIRECTION('center_axis',(1.,0.,-1.48029736616688E-16));
+#1291=DIRECTION('ref_axis',(-1.48029736616688E-16,0.,-1.));
+#1292=DIRECTION('',(1.48029736616688E-16,-2.22044604925031E-16,1.));
+#1293=DIRECTION('',(0.,1.,0.));
+#1294=DIRECTION('',(0.,1.,0.));
+#1295=DIRECTION('center_axis',(0.,1.,0.));
+#1296=DIRECTION('ref_axis',(1.,0.,0.));
+#1297=DIRECTION('center_axis',(0.,-1.,-2.22044604925031E-16));
+#1298=DIRECTION('ref_axis',(1.,0.,0.));
+#1299=DIRECTION('',(0.,1.,0.));
+#1300=DIRECTION('center_axis',(-1.,0.,-1.48029736616688E-16));
+#1301=DIRECTION('ref_axis',(-1.48029736616688E-16,0.,1.));
+#1302=DIRECTION('',(1.48029736616688E-16,2.22044604925031E-16,-1.));
+#1303=DIRECTION('',(0.,1.,0.));
+#1304=DIRECTION('center_axis',(0.,1.,0.));
+#1305=DIRECTION('ref_axis',(-1.,0.,0.));
+#1306=DIRECTION('center_axis',(0.,-1.,-2.22044604925031E-16));
+#1307=DIRECTION('ref_axis',(-1.,0.,0.));
+#1308=DIRECTION('center_axis',(0.,-2.01858731750028E-16,1.));
+#1309=DIRECTION('ref_axis',(0.,-1.,-2.01858731750028E-16));
+#1310=DIRECTION('center_axis',(0.,2.01858731750028E-16,-1.));
+#1311=DIRECTION('ref_axis',(-1.,0.,0.));
+#1312=DIRECTION('center_axis',(0.,2.01858731750028E-16,-1.));
+#1313=DIRECTION('ref_axis',(-1.,0.,0.));
+#1314=DIRECTION('center_axis',(0.,0.,1.));
+#1315=DIRECTION('ref_axis',(-1.,0.,0.));
+#1316=DIRECTION('',(0.,0.,1.));
+#1317=DIRECTION('center_axis',(0.,0.,1.));
+#1318=DIRECTION('ref_axis',(-1.,0.,0.));
+#1319=DIRECTION('',(0.,0.,1.));
+#1320=DIRECTION('center_axis',(0.,-1.,-1.77635683940025E-15));
+#1321=DIRECTION('ref_axis',(0.,1.77635683940025E-15,-1.));
+#1322=DIRECTION('center_axis',(0.,1.,2.22044604925031E-16));
+#1323=DIRECTION('ref_axis',(0.,-2.22044604925031E-16,1.));
+#1324=CARTESIAN_POINT('',(0.,0.,0.));
+#1325=CARTESIAN_POINT('Origin',(2.,-49.9129590869963,-7.82025180641496));
+#1326=CARTESIAN_POINT('',(2.,-49.9129590869963,-5.82025180641496));
+#1327=CARTESIAN_POINT('',(2.,-51.9129590869963,-7.82025180641497));
+#1328=CARTESIAN_POINT('Origin',(2.,-49.9129590869963,-7.82025180641496));
+#1329=CARTESIAN_POINT('',(0.,-49.9129590869963,-7.82025180641496));
+#1330=CARTESIAN_POINT('Origin',(2.,-49.9129590869963,-7.82025180641496));
+#1331=CARTESIAN_POINT('Origin',(2.,-49.9129590869963,-7.82025180641496));
+#1332=CARTESIAN_POINT('Origin',(13.,-16.1237455246232,19.1405346312119));
+#1333=CARTESIAN_POINT('',(13.,-40.9129590869963,-2.82025180641496));
+#1334=CARTESIAN_POINT('',(13.,-43.9129590869963,-5.82025180641496));
+#1335=CARTESIAN_POINT('',(13.,-17.5379590869963,20.554748193585));
+#1336=CARTESIAN_POINT('',(15.,-41.0845319622501,-5.82025180641496));
+#1337=CARTESIAN_POINT('Origin',(13.,-41.0845319622501,-5.82025180641496));
+#1338=CARTESIAN_POINT('',(15.,-38.9129590869963,-3.64867893116115));
+#1339=CARTESIAN_POINT('',(15.,-16.1237455246232,19.1405346312119));
+#1340=CARTESIAN_POINT('Origin',(13.,-38.9129590869963,-3.64867893116115));
+#1341=CARTESIAN_POINT('Origin',(13.,37.0870409130037,84.8913942896513));
+#1342=CARTESIAN_POINT('',(13.,39.0870409130037,84.8913942896513));
+#1343=CARTESIAN_POINT('',(15.,41.0870409130037,84.8913942896513));
+#1344=CARTESIAN_POINT('Origin',(13.,41.0870409130037,84.8913942896513));
+#1345=CARTESIAN_POINT('',(13.,38.3482261631926,83.3391662894188));
+#1346=CARTESIAN_POINT('Origin',(13.,37.0870409130037,84.8913942896513));
+#1347=CARTESIAN_POINT('',(15.,39.6094114133815,81.7869382891862));
+#1348=CARTESIAN_POINT('Origin',(13.,39.6094114133815,81.7869382891862));
+#1349=CARTESIAN_POINT('Origin',(15.,37.0870409130037,84.8913942896513));
+#1350=CARTESIAN_POINT('Origin',(2.,-21.1629590869963,-7.82025180641496));
+#1351=CARTESIAN_POINT('',(0.,-43.0845319622501,-7.82025180641496));
+#1352=CARTESIAN_POINT('',(0.,-21.1629590869963,-7.82025180641496));
+#1353=CARTESIAN_POINT('',(2.,-43.9129590869963,-5.82025180641496));
+#1354=CARTESIAN_POINT('',(2.,-21.1629590869963,-5.82025180641496));
+#1355=CARTESIAN_POINT('Origin',(2.,-43.0845319622501,-7.82025180641496));
+#1356=CARTESIAN_POINT('Origin',(13.,-38.9129590869963,17.9875122576292));
+#1357=CARTESIAN_POINT('',(13.,-40.1741443371853,19.5397402578617));
+#1358=CARTESIAN_POINT('',(15.,-38.9129590869963,17.9875122576292));
+#1359=CARTESIAN_POINT('Origin',(13.,-38.9129590869963,17.9875122576292));
+#1360=CARTESIAN_POINT('',(13.,-40.9129590869963,17.9875122576292));
+#1361=CARTESIAN_POINT('Origin',(13.,-38.9129590869963,17.9875122576292));
+#1362=CARTESIAN_POINT('Origin',(13.,-38.9129590869963,17.9875122576292));
+#1363=CARTESIAN_POINT('Origin',(2.,37.0870409130037,84.8913942896513));
+#1364=CARTESIAN_POINT('',(2.,39.0870409130037,84.8913942896513));
+#1365=CARTESIAN_POINT('',(2.,38.3482261631926,83.3391662894188));
+#1366=CARTESIAN_POINT('Origin',(2.,37.0870409130037,84.8913942896513));
+#1367=CARTESIAN_POINT('',(0.,41.0870409130037,84.8913942896513));
+#1368=CARTESIAN_POINT('Origin',(2.,41.0870409130037,84.8913942896513));
+#1369=CARTESIAN_POINT('',(0.,39.6094114133815,81.7869382891862));
+#1370=CARTESIAN_POINT('Origin',(0.,37.0870409130037,84.8913942896513));
+#1371=CARTESIAN_POINT('Origin',(2.,39.6094114133815,81.7869382891862));
+#1372=CARTESIAN_POINT('Origin',(2.,41.0870409130037,86.679748193585));
+#1373=CARTESIAN_POINT('',(0.,41.0870409130037,119.179748193585));
+#1374=CARTESIAN_POINT('',(0.,41.0870409130037,86.679748193585));
+#1375=CARTESIAN_POINT('',(2.,39.0870409130037,117.179748193585));
+#1376=CARTESIAN_POINT('',(2.,39.0870409130037,86.679748193585));
+#1377=CARTESIAN_POINT('Origin',(2.,41.0870409130037,117.179748193585));
+#1378=CARTESIAN_POINT('Origin',(2.,-38.9129590869963,17.9875122576292));
+#1379=CARTESIAN_POINT('',(2.,-40.1741443371852,19.5397402578617));
+#1380=CARTESIAN_POINT('',(2.,-40.9129590869963,17.9875122576292));
+#1381=CARTESIAN_POINT('Origin',(2.,-38.9129590869963,17.9875122576292));
+#1382=CARTESIAN_POINT('',(0.,-38.9129590869963,17.9875122576292));
+#1383=CARTESIAN_POINT('Origin',(2.,-38.9129590869963,17.9875122576292));
+#1384=CARTESIAN_POINT('Origin',(2.,-38.9129590869963,17.9875122576292));
+#1385=CARTESIAN_POINT('Origin',(2.,20.8682042141909,66.5597074398438));
+#1386=CARTESIAN_POINT('',(2.,19.6070189640019,68.1119354400763));
+#1387=CARTESIAN_POINT('',(0.,20.8682042141909,66.5597074398438));
+#1388=CARTESIAN_POINT('Origin',(2.,-38.9129590869963,36.5596007336126));
+#1389=CARTESIAN_POINT('',(2.,-40.9129590869963,-2.82025180641496));
+#1390=CARTESIAN_POINT('',(2.,-40.9129590869963,36.5596007336126));
+#1391=CARTESIAN_POINT('',(0.,-38.9129590869963,-3.64867893116115));
+#1392=CARTESIAN_POINT('',(0.,-38.9129590869963,36.5596007336126));
+#1393=CARTESIAN_POINT('Origin',(2.,-38.9129590869963,-3.64867893116115));
+#1394=CARTESIAN_POINT('Origin',(0.,-38.9129590869963,17.9875122576292));
+#1395=CARTESIAN_POINT('',(0.,-40.1741443371853,19.5397402578617));
+#1396=CARTESIAN_POINT('',(0.,-40.9129590869963,17.9875122576292));
+#1397=CARTESIAN_POINT('Origin',(2.,-16.1237455246232,19.1405346312119));
+#1398=CARTESIAN_POINT('',(2.,-17.5379590869963,20.554748193585));
+#1399=CARTESIAN_POINT('',(0.,-16.1237455246232,19.1405346312119));
+#1400=CARTESIAN_POINT('Origin',(0.,37.0870409130037,84.8913942896513));
+#1401=CARTESIAN_POINT('',(0.,39.0870409130037,84.8913942896513));
+#1402=CARTESIAN_POINT('',(0.,38.3482261631926,83.3391662894188));
+#1403=CARTESIAN_POINT('Origin',(13.,-38.9129590869963,36.5596007336126));
+#1404=CARTESIAN_POINT('',(15.,-38.9129590869963,36.5596007336126));
+#1405=CARTESIAN_POINT('',(13.,-40.9129590869963,36.5596007336126));
+#1406=CARTESIAN_POINT('Origin',(13.,20.8682042141909,66.5597074398438));
+#1407=CARTESIAN_POINT('',(15.,20.8682042141909,66.5597074398438));
+#1408=CARTESIAN_POINT('',(13.,19.6070189640019,68.1119354400763));
+#1409=CARTESIAN_POINT('Origin',(0.,41.0870409130037,117.179748193585));
+#1410=CARTESIAN_POINT('',(15.,41.0870409130037,119.179748193585));
+#1411=CARTESIAN_POINT('',(0.,41.0870409130037,119.179748193585));
+#1412=CARTESIAN_POINT('',(13.,39.0870409130037,117.179748193585));
+#1413=CARTESIAN_POINT('',(0.,39.0870409130037,117.179748193585));
+#1414=CARTESIAN_POINT('Origin',(13.,41.0870409130037,117.179748193585));
+#1415=CARTESIAN_POINT('Origin',(13.,41.0870409130037,86.679748193585));
+#1416=CARTESIAN_POINT('',(13.,39.0870409130037,86.679748193585));
+#1417=CARTESIAN_POINT('',(15.,41.0870409130037,86.679748193585));
+#1418=CARTESIAN_POINT('Origin',(2.,-49.9129590869964,24.179748193585));
+#1419=CARTESIAN_POINT('',(0.,-49.9129590869963,-10.820251806415));
+#1420=CARTESIAN_POINT('',(2.,-51.9129590869963,-10.820251806415));
+#1421=CARTESIAN_POINT('Origin',(2.,-49.9129590869963,-10.820251806415));
+#1422=CARTESIAN_POINT('',(2.,-51.9129590869964,24.179748193585));
+#1423=CARTESIAN_POINT('',(0.,-49.9129590869964,24.179748193585));
+#1424=CARTESIAN_POINT('Origin',(0.,-49.9129590869963,-7.82025180641496));
+#1425=CARTESIAN_POINT('',(15.,-51.9129590869963,-7.82025180641497));
+#1426=CARTESIAN_POINT('',(15.,-49.9129590869963,-5.82025180641496));
+#1427=CARTESIAN_POINT('Origin',(15.,-49.9129590869963,-7.82025180641496));
+#1428=CARTESIAN_POINT('',(7.5,-49.9129590869963,-5.82025180641496));
+#1429=CARTESIAN_POINT('',(0.,-49.9129590869963,-5.82025180641496));
+#1430=CARTESIAN_POINT('',(0.,-49.9129590869963,-5.82025180641496));
+#1431=CARTESIAN_POINT('',(0.,-51.9129590869963,-7.82025180641497));
+#1432=CARTESIAN_POINT('Origin',(0.,49.0870409130037,119.179748193585));
+#1433=CARTESIAN_POINT('',(15.,49.0870409130037,119.179748193585));
+#1434=CARTESIAN_POINT('',(15.,49.0870409130037,119.179748193585));
+#1435=CARTESIAN_POINT('',(0.,49.0870409130037,119.179748193585));
+#1436=CARTESIAN_POINT('',(0.,49.0870409130037,119.179748193585));
+#1437=CARTESIAN_POINT('',(0.,49.0870409130037,119.179748193585));
+#1438=CARTESIAN_POINT('Origin',(15.,-1.41295908699631,54.179748193585));
+#1439=CARTESIAN_POINT('',(15.,-40.9129590869963,-5.82025180641496));
+#1440=CARTESIAN_POINT('',(15.,-51.9129590869963,-10.820251806415));
+#1441=CARTESIAN_POINT('',(15.,-51.9129590869963,-5.82025180641496));
+#1442=CARTESIAN_POINT('',(15.,-19.9129590869963,-10.820251806415));
+#1443=CARTESIAN_POINT('',(15.,-51.9129590869963,-10.820251806415));
+#1444=CARTESIAN_POINT('',(15.,-19.9129590869963,-5.82025180641496));
+#1445=CARTESIAN_POINT('',(15.,-19.9129590869963,-10.820251806415));
+#1446=CARTESIAN_POINT('',(15.,-30.7413862117425,-5.82025180641496));
+#1447=CARTESIAN_POINT('',(15.,-19.9129590869963,-5.82025180641496));
+#1448=CARTESIAN_POINT('',(15.,-32.9129590869963,-3.64867893116116));
+#1449=CARTESIAN_POINT('',(15.,-38.4521726493694,1.89053463121192));
+#1450=CARTESIAN_POINT('',(15.,-32.9129590869963,13.227807177574));
+#1451=CARTESIAN_POINT('',(15.,-32.9129590869963,24.179748193585));
+#1452=CARTESIAN_POINT('',(15.,-31.4353295873742,16.3322631780391));
+#1453=CARTESIAN_POINT('Origin',(15.,-28.9129590869963,13.227807177574));
+#1454=CARTESIAN_POINT('',(15.,49.0870409130037,81.7566892095961));
+#1455=CARTESIAN_POINT('',(15.,-13.5012031607147,30.9037408996999));
+#1456=CARTESIAN_POINT('',(15.,49.0870409130037,79.1797481935851));
+#1457=CARTESIAN_POINT('Origin',(0.,-40.9129590869963,18.9394532736402));
+#1458=CARTESIAN_POINT('',(0.,-40.9129590869963,-2.82025180641496));
+#1459=CARTESIAN_POINT('Origin',(0.,-42.4129590869963,-4.32025180641496));
+#1460=CARTESIAN_POINT('',(0.,-43.9129590869963,-5.82025180641496));
+#1461=CARTESIAN_POINT('Origin',(0.,39.0870409130037,119.179748193585));
+#1462=CARTESIAN_POINT('',(10.,39.0870409130037,108.836570095682));
+#1463=CARTESIAN_POINT('',(10.,39.0870409130037,93.8365700956818));
+#1464=CARTESIAN_POINT('',(10.,39.0870409130037,114.008159144633));
+#1465=CARTESIAN_POINT('',(5.,39.0870409130037,93.8365700956818));
+#1466=CARTESIAN_POINT('Origin',(7.5,39.0870409130037,93.8365700956818));
+#1467=CARTESIAN_POINT('',(5.,39.0870409130037,108.836570095682));
+#1468=CARTESIAN_POINT('',(5.,39.0870409130037,106.508159144633));
+#1469=CARTESIAN_POINT('Origin',(7.5,39.0870409130037,108.836570095682));
+#1470=CARTESIAN_POINT('Origin',(0.,39.0870409130037,83.9394532736403));
+#1471=CARTESIAN_POINT('Origin',(13.,-28.9129590869963,13.227807177574));
+#1472=CARTESIAN_POINT('',(13.,-30.9129590869963,13.227807177574));
+#1473=CARTESIAN_POINT('Origin',(13.,-32.9129590869963,13.227807177574));
+#1474=CARTESIAN_POINT('',(13.,-30.1741443371852,14.7800351778065));
+#1475=CARTESIAN_POINT('Origin',(13.,-28.9129590869963,13.227807177574));
+#1476=CARTESIAN_POINT('Origin',(13.,-31.4353295873742,16.3322631780391));
+#1477=CARTESIAN_POINT('Origin',(2.,-10.6629590869963,-7.82025180641495));
+#1478=CARTESIAN_POINT('',(0.,-21.9129590869963,-7.82025180641496));
+#1479=CARTESIAN_POINT('',(0.,-28.7413862117425,-7.82025180641496));
+#1480=CARTESIAN_POINT('',(0.,-10.6629590869963,-7.82025180641495));
+#1481=CARTESIAN_POINT('',(2.,-27.9129590869963,-5.82025180641496));
+#1482=CARTESIAN_POINT('Origin',(2.,-28.7413862117425,-7.82025180641496));
+#1483=CARTESIAN_POINT('',(2.,-19.9129590869963,-5.82025180641496));
+#1484=CARTESIAN_POINT('',(2.,-10.6629590869963,-5.82025180641495));
+#1485=CARTESIAN_POINT('Origin',(2.,-21.9129590869963,-7.82025180641496));
+#1486=CARTESIAN_POINT('Origin',(1.99999999999998,-28.9129590869963,13.227807177574));
+#1487=CARTESIAN_POINT('',(2.,-30.9129590869963,13.227807177574));
+#1488=CARTESIAN_POINT('',(2.,-30.1741443371852,14.7800351778065));
+#1489=CARTESIAN_POINT('Origin',(2.,-28.9129590869963,13.227807177574));
+#1490=CARTESIAN_POINT('',(0.,-32.9129590869963,13.227807177574));
+#1491=CARTESIAN_POINT('Origin',(2.,-32.9129590869963,13.227807177574));
+#1492=CARTESIAN_POINT('',(0.,-31.4353295873742,16.3322631780391));
+#1493=CARTESIAN_POINT('Origin',(0.,-28.9129590869963,13.227807177574));
+#1494=CARTESIAN_POINT('Origin',(2.,-31.4353295873742,16.3322631780391));
+#1495=CARTESIAN_POINT('Origin',(2.,-32.9129590869963,24.179748193585));
+#1496=CARTESIAN_POINT('',(0.,-32.9129590869963,-3.64867893116117));
+#1497=CARTESIAN_POINT('',(0.,-32.9129590869963,24.179748193585));
+#1498=CARTESIAN_POINT('',(2.,-30.9129590869963,-2.82025180641496));
+#1499=CARTESIAN_POINT('',(2.,-30.9129590869963,24.179748193585));
+#1500=CARTESIAN_POINT('Origin',(2.,-32.9129590869963,-3.64867893116117));
+#1501=CARTESIAN_POINT('Origin',(2.,-38.4521726493694,1.89053463121192));
+#1502=CARTESIAN_POINT('',(0.,-38.4521726493694,1.89053463121192));
+#1503=CARTESIAN_POINT('',(2.,-37.0379590869963,3.30474819358503));
+#1504=CARTESIAN_POINT('Origin',(2.,-13.5012031607147,30.9037408996999));
+#1505=CARTESIAN_POINT('',(2.,48.3482261631926,78.5794612093636));
+#1506=CARTESIAN_POINT('',(2.,-12.2400179105257,29.3515128994674));
+#1507=CARTESIAN_POINT('',(0.,49.0870409130037,81.7566892095961));
+#1508=CARTESIAN_POINT('',(0.,-13.5012031607147,30.9037408996999));
+#1509=CARTESIAN_POINT('',(0.447771999767468,49.0870409130037,80.1316892095961));
+#1510=CARTESIAN_POINT('Origin',(2.,49.0870409130037,81.7566892095961));
+#1511=CARTESIAN_POINT('Origin',(2.,47.0870409130037,80.1316892095961));
+#1512=CARTESIAN_POINT('Origin',(0.,-28.9129590869963,13.227807177574));
+#1513=CARTESIAN_POINT('',(0.,-30.9129590869963,13.227807177574));
+#1514=CARTESIAN_POINT('',(0.,-30.1741443371852,14.7800351778065));
+#1515=CARTESIAN_POINT('Origin',(0.,47.0870409130037,80.1316892095961));
+#1516=CARTESIAN_POINT('',(13.,48.3482261631926,78.5794612093636));
+#1517=CARTESIAN_POINT('',(0.,48.3482261631926,78.5794612093636));
+#1518=CARTESIAN_POINT('',(14.5522280002325,49.0870409130037,80.1316892095961));
+#1519=CARTESIAN_POINT('',(0.,49.0870409130037,80.1316892095961));
+#1520=CARTESIAN_POINT('Origin',(13.,47.0870409130037,80.1316892095961));
+#1521=CARTESIAN_POINT('Origin',(13.,-13.5012031607147,30.9037408996999));
+#1522=CARTESIAN_POINT('',(13.,-12.2400179105257,29.3515128994674));
+#1523=CARTESIAN_POINT('Origin',(13.,49.0870409130037,81.7566892095961));
+#1524=CARTESIAN_POINT('Origin',(13.,-32.9129590869963,24.179748193585));
+#1525=CARTESIAN_POINT('',(13.,-30.9129590869963,-2.82025180641496));
+#1526=CARTESIAN_POINT('',(13.,-30.9129590869963,24.179748193585));
+#1527=CARTESIAN_POINT('Origin',(13.,-32.9129590869963,-3.64867893116116));
+#1528=CARTESIAN_POINT('Origin',(2.,-21.9129590869963,21.679748193585));
+#1529=CARTESIAN_POINT('',(2.,-19.9129590869963,-10.820251806415));
+#1530=CARTESIAN_POINT('',(2.,-19.9129590869963,21.679748193585));
+#1531=CARTESIAN_POINT('',(0.,-21.9129590869963,-10.820251806415));
+#1532=CARTESIAN_POINT('Origin',(2.,-21.9129590869963,-10.8202518064149));
+#1533=CARTESIAN_POINT('',(0.,-21.9129590869963,21.679748193585));
+#1534=CARTESIAN_POINT('Origin',(13.,-38.4521726493694,1.89053463121192));
+#1535=CARTESIAN_POINT('',(13.,-27.9129590869963,-5.82025180641496));
+#1536=CARTESIAN_POINT('Origin',(13.,-30.7413862117425,-5.82025180641496));
+#1537=CARTESIAN_POINT('',(13.,-37.0379590869963,3.30474819358502));
+#1538=CARTESIAN_POINT('Origin',(0.,-1.41295908699631,54.179748193585));
+#1539=CARTESIAN_POINT('',(0.,49.0870409130037,79.1797481935851));
+#1540=CARTESIAN_POINT('',(0.,-51.9129590869963,-10.820251806415));
+#1541=CARTESIAN_POINT('Origin',(0.,-51.9129590869963,-10.820251806415));
+#1542=CARTESIAN_POINT('',(0.,-19.9129590869963,-10.820251806415));
+#1543=CARTESIAN_POINT('',(0.,-51.9129590869963,-10.820251806415));
+#1544=CARTESIAN_POINT('',(10.,-47.4129590869963,-10.820251806415));
+#1545=CARTESIAN_POINT('Origin',(7.5,-47.4129590869963,-10.820251806415));
+#1546=CARTESIAN_POINT('',(10.,-24.4129590869963,-10.820251806415));
+#1547=CARTESIAN_POINT('Origin',(7.5,-24.4129590869963,-10.820251806415));
+#1548=CARTESIAN_POINT('Origin',(0.,-19.9129590869963,-10.820251806415));
+#1549=CARTESIAN_POINT('',(0.,-19.9129590869963,-5.82025180641496));
+#1550=CARTESIAN_POINT('Origin',(0.,-19.9129590869963,-5.82025180641496));
+#1551=CARTESIAN_POINT('',(0.,-27.9129590869963,-5.82025180641496));
+#1552=CARTESIAN_POINT('',(10.,-24.4129590869963,-5.82025180641496));
+#1553=CARTESIAN_POINT('Origin',(7.5,-24.4129590869963,-5.82025180641496));
+#1554=CARTESIAN_POINT('Origin',(0.,-30.9129590869963,-5.82025180641496));
+#1555=CARTESIAN_POINT('',(0.,-30.9129590869963,-2.82025180641496));
+#1556=CARTESIAN_POINT('Origin',(0.,-29.4129590869963,-4.32025180641496));
+#1557=CARTESIAN_POINT('Origin',(0.,-30.9129590869963,14.179748193585));
+#1558=CARTESIAN_POINT('Origin',(10.,39.0870409130037,108.836570095682));
+#1559=CARTESIAN_POINT('',(10.,49.0870409130037,93.8365700956818));
+#1560=CARTESIAN_POINT('',(10.,49.0870409130037,108.836570095682));
+#1561=CARTESIAN_POINT('',(10.,49.0870409130037,94.0081591446334));
+#1562=CARTESIAN_POINT('',(10.,39.0870409130037,93.8365700956818));
+#1563=CARTESIAN_POINT('',(10.,39.0870409130037,108.836570095682));
+#1564=CARTESIAN_POINT('Origin',(7.5,39.0870409130037,108.836570095682));
+#1565=CARTESIAN_POINT('',(5.,49.0870409130037,108.836570095682));
+#1566=CARTESIAN_POINT('Origin',(7.5,49.0870409130037,108.836570095682));
+#1567=CARTESIAN_POINT('',(5.,39.0870409130037,108.836570095682));
+#1568=CARTESIAN_POINT('Origin',(5.,39.0870409130037,93.8365700956818));
+#1569=CARTESIAN_POINT('',(5.,49.0870409130037,93.8365700956818));
+#1570=CARTESIAN_POINT('',(5.,49.0870409130037,86.5081591446334));
+#1571=CARTESIAN_POINT('',(5.,39.0870409130037,93.8365700956818));
+#1572=CARTESIAN_POINT('Origin',(7.5,39.0870409130037,93.8365700956818));
+#1573=CARTESIAN_POINT('Origin',(7.5,49.0870409130037,93.8365700956818));
+#1574=CARTESIAN_POINT('Origin',(0.,-40.9129590869963,-5.82025180641496));
+#1575=CARTESIAN_POINT('',(10.,-47.4129590869963,-5.82025180641496));
+#1576=CARTESIAN_POINT('Origin',(7.5,-47.4129590869963,-5.82025180641496));
+#1577=CARTESIAN_POINT('Origin',(7.5,-47.4129590869963,-5.82025180641496));
+#1578=CARTESIAN_POINT('Origin',(7.5,-24.4129590869963,-10.820251806415));
+#1579=CARTESIAN_POINT('',(10.,-24.4129590869963,-10.820251806415));
+#1580=CARTESIAN_POINT('Origin',(7.5,-47.4129590869963,-10.820251806415));
+#1581=CARTESIAN_POINT('',(10.,-47.4129590869963,-10.820251806415));
+#1582=CARTESIAN_POINT('Origin',(0.,-51.9129590869963,-5.82025180641496));
+#1583=CARTESIAN_POINT('Origin',(0.,49.0870409130037,79.1797481935851));
+#1584=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1588,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#1585=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1588,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#1586=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1584))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#1588,#1590,#1591))
+REPRESENTATION_CONTEXT('','3D')
+);
+#1587=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1585))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#1588,#1590,#1591))
+REPRESENTATION_CONTEXT('','3D')
+);
+#1588=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.MILLI.,.METRE.)
+);
+#1589=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.CENTI.,.METRE.)
+);
+#1590=(
+NAMED_UNIT(*)
+PLANE_ANGLE_UNIT()
+SI_UNIT($,.RADIAN.)
+);
+#1591=(
+NAMED_UNIT(*)
+SI_UNIT($,.STERADIAN.)
+SOLID_ANGLE_UNIT()
+);
+#1592=SHAPE_DEFINITION_REPRESENTATION(#1593,#1594);
+#1593=PRODUCT_DEFINITION_SHAPE('',$,#1596);
+#1594=SHAPE_REPRESENTATION('',(#929),#1586);
+#1595=PRODUCT_DEFINITION_CONTEXT('part definition',#1600,'design');
+#1596=PRODUCT_DEFINITION('arm','arm',#1597,#1595);
+#1597=PRODUCT_DEFINITION_FORMATION('',$,#1602);
+#1598=PRODUCT_RELATED_PRODUCT_CATEGORY('arm','arm',(#1602));
+#1599=APPLICATION_PROTOCOL_DEFINITION('international standard',
+'automotive_design',2009,#1600);
+#1600=APPLICATION_CONTEXT(
+'Core Data for Automotive Mechanical Design Process');
+#1601=PRODUCT_CONTEXT('part definition',#1600,'mechanical');
+#1602=PRODUCT('arm','arm',$,(#1601));
+#1603=PRESENTATION_STYLE_ASSIGNMENT((#1604));
+#1604=SURFACE_STYLE_USAGE(.BOTH.,#1607);
+#1605=SURFACE_STYLE_RENDERING_WITH_PROPERTIES($,#1611,(#1606));
+#1606=SURFACE_STYLE_TRANSPARENT(0.);
+#1607=SURFACE_SIDE_STYLE('',(#1608,#1605));
+#1608=SURFACE_STYLE_FILL_AREA(#1609);
+#1609=FILL_AREA_STYLE('',(#1610));
+#1610=FILL_AREA_STYLE_COLOUR('',#1611);
+#1611=COLOUR_RGB('',0.749019607843137,0.749019607843137,0.749019607843137);
+ENDSEC;
+END-ISO-10303-21;
diff --git a/Komponenten/base.ipt b/Komponenten/base.ipt
new file mode 100644
index 0000000000000000000000000000000000000000..0fc24c100a38caf09e5e294b55b9731bb2cbe1b5
Binary files /dev/null and b/Komponenten/base.ipt differ
diff --git a/Komponenten/base.stp b/Komponenten/base.stp
new file mode 100644
index 0000000000000000000000000000000000000000..8620e7f38da80c1606eaf06912def901632b905d
--- /dev/null
+++ b/Komponenten/base.stp
@@ -0,0 +1,8139 @@
+ISO-10303-21;
+HEADER;
+/* Generated by software containing ST-Developer
+ * from STEP Tools, Inc. (www.steptools.com) 
+ */
+
+FILE_DESCRIPTION(
+/* description */ (''),
+/* implementation_level */ '2;1');
+
+FILE_NAME(
+/* name */ 'base.stp',
+/* time_stamp */ '2025-01-13T19:50:07+01:00',
+/* author */ ('seb'),
+/* organization */ (''),
+/* preprocessor_version */ 'ST-DEVELOPER v20',
+/* originating_system */ 'Autodesk Inventor 2025',
+/* authorisation */ '');
+
+FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }'));
+ENDSEC;
+
+DATA;
+#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#102,#103,
+#104,#105,#106,#107,#108,#109,#110,#111,#112,#113,#114,#115,#116,#117,#118,
+#119,#120,#121,#122,#123,#124,#125,#126,#127,#128,#129,#130,#131,#132,#133,
+#134,#135,#136,#137,#138),#7523);
+#11=GEOMETRICALLY_BOUNDED_WIREFRAME_SHAPE_REPRESENTATION('',(#12),#7522);
+#12=GEOMETRIC_CURVE_SET('Skizze2',(#96,#97,#1556,#98,#1558,#99,#1560,#1561,
+#16,#17,#100,#101,#1564,#1565,#1566,#1567,#1568,#18,#19,#20,#21,#22,#23,
+#24,#25,#26,#27,#28,#29,#30,#31,#32,#33,#34,#35,#36,#37,#38,#39,#40,#41,
+#42,#43,#44,#45,#46,#47,#48,#49,#50,#51,#52,#53,#54,#55,#56,#57,#58,#59,
+#60,#61,#62,#63,#64,#65,#66,#67,#68,#69,#70,#71,#72,#73,#74,#75,#1569,#1570,
+#1571,#1572,#1573,#1574,#1575,#1576,#76,#77,#78,#79,#80,#81,#82,#83,#84,
+#85,#86,#87,#88,#89,#90,#91,#92,#93,#94,#95,#7511,#7512,#7513,#7514,#7515,
+#7516,#7517,#7518,#7519));
+#13=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#7530,#15);
+#14=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#7530,#11);
+#15=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#139),#7522);
+#16=POLYLINE('',(#7332,#7333));
+#17=POLYLINE('',(#7334,#7335));
+#18=POLYLINE('',(#7347,#7348));
+#19=POLYLINE('',(#7349,#7350));
+#20=POLYLINE('',(#7351,#7352));
+#21=POLYLINE('',(#7353,#7354));
+#22=POLYLINE('',(#7355,#7356));
+#23=POLYLINE('',(#7357,#7358));
+#24=POLYLINE('',(#7359,#7360));
+#25=POLYLINE('',(#7361,#7362));
+#26=POLYLINE('',(#7363,#7364));
+#27=POLYLINE('',(#7365,#7366));
+#28=POLYLINE('',(#7367,#7368));
+#29=POLYLINE('',(#7369,#7370));
+#30=POLYLINE('',(#7371,#7372));
+#31=POLYLINE('',(#7373,#7374));
+#32=POLYLINE('',(#7375,#7376));
+#33=POLYLINE('',(#7377,#7378));
+#34=POLYLINE('',(#7379,#7380));
+#35=POLYLINE('',(#7381,#7382));
+#36=POLYLINE('',(#7383,#7384));
+#37=POLYLINE('',(#7385,#7386));
+#38=POLYLINE('',(#7387,#7388));
+#39=POLYLINE('',(#7389,#7390));
+#40=POLYLINE('',(#7391,#7392));
+#41=POLYLINE('',(#7393,#7394));
+#42=POLYLINE('',(#7395,#7396));
+#43=POLYLINE('',(#7397,#7398));
+#44=POLYLINE('',(#7399,#7400));
+#45=POLYLINE('',(#7401,#7402));
+#46=POLYLINE('',(#7403,#7404));
+#47=POLYLINE('',(#7405,#7406));
+#48=POLYLINE('',(#7407,#7408));
+#49=POLYLINE('',(#7409,#7410));
+#50=POLYLINE('',(#7411,#7412));
+#51=POLYLINE('',(#7413,#7414));
+#52=POLYLINE('',(#7415,#7416));
+#53=POLYLINE('',(#7417,#7418));
+#54=POLYLINE('',(#7419,#7420));
+#55=POLYLINE('',(#7421,#7422));
+#56=POLYLINE('',(#7423,#7424));
+#57=POLYLINE('',(#7425,#7426));
+#58=POLYLINE('',(#7427,#7428));
+#59=POLYLINE('',(#7429,#7430));
+#60=POLYLINE('',(#7431,#7432));
+#61=POLYLINE('',(#7433,#7434));
+#62=POLYLINE('',(#7435,#7436));
+#63=POLYLINE('',(#7437,#7438));
+#64=POLYLINE('',(#7439,#7440));
+#65=POLYLINE('',(#7441,#7442));
+#66=POLYLINE('',(#7443,#7444));
+#67=POLYLINE('',(#7445,#7446));
+#68=POLYLINE('',(#7447,#7448));
+#69=POLYLINE('',(#7449,#7450));
+#70=POLYLINE('',(#7451,#7452));
+#71=POLYLINE('',(#7453,#7454));
+#72=POLYLINE('',(#7455,#7456));
+#73=POLYLINE('',(#7457,#7458));
+#74=POLYLINE('',(#7459,#7460));
+#75=POLYLINE('',(#7461,#7462));
+#76=POLYLINE('',(#7471,#7472));
+#77=POLYLINE('',(#7473,#7474));
+#78=POLYLINE('',(#7475,#7476));
+#79=POLYLINE('',(#7477,#7478));
+#80=POLYLINE('',(#7479,#7480));
+#81=POLYLINE('',(#7481,#7482));
+#82=POLYLINE('',(#7483,#7484));
+#83=POLYLINE('',(#7485,#7486));
+#84=POLYLINE('',(#7487,#7488));
+#85=POLYLINE('',(#7489,#7490));
+#86=POLYLINE('',(#7491,#7492));
+#87=POLYLINE('',(#7493,#7494));
+#88=POLYLINE('',(#7495,#7496));
+#89=POLYLINE('',(#7497,#7498));
+#90=POLYLINE('',(#7499,#7500));
+#91=POLYLINE('',(#7501,#7502));
+#92=POLYLINE('',(#7503,#7504));
+#93=POLYLINE('',(#7505,#7506));
+#94=POLYLINE('',(#7507,#7508));
+#95=POLYLINE('',(#7509,#7510));
+#96=TRIMMED_CURVE('',#1554,(#7317,PARAMETER_VALUE(4.34022044642436)),(#7318,
+PARAMETER_VALUE(5.08455751434501)),.T.,.PARAMETER.);
+#97=TRIMMED_CURVE('',#1555,(#7320,PARAMETER_VALUE(4.38209162555544)),(#7321,
+PARAMETER_VALUE(5.04268633521394)),.T.,.PARAMETER.);
+#98=TRIMMED_CURVE('',#1557,(#7324,PARAMETER_VALUE(5.08455751434501)),(#7325,
+PARAMETER_VALUE(6.28318530717959)),.T.,.PARAMETER.);
+#99=TRIMMED_CURVE('',#1559,(#7328,PARAMETER_VALUE(0.)),(#7329,
+PARAMETER_VALUE(1.90109368162415)),.T.,.PARAMETER.);
+#100=TRIMMED_CURVE('',#1562,(#7337,PARAMETER_VALUE(4.31950186848081)),(#7338,
+PARAMETER_VALUE(5.10527609228857)),.T.,.PARAMETER.);
+#101=TRIMMED_CURVE('',#1563,(#7340,PARAMETER_VALUE(4.31950186848082)),(#7341,
+PARAMETER_VALUE(5.10527609228856)),.T.,.PARAMETER.);
+#102=STYLED_ITEM('',(#7539),#139);
+#103=STYLED_ITEM('',(#7540),#96);
+#104=STYLED_ITEM('',(#7541),#97);
+#105=STYLED_ITEM('',(#7540),#98);
+#106=STYLED_ITEM('',(#7540),#99);
+#107=STYLED_ITEM('',(#7540),#16);
+#108=STYLED_ITEM('',(#7540),#17);
+#109=STYLED_ITEM('',(#7542),#19);
+#110=STYLED_ITEM('',(#7542),#21);
+#111=STYLED_ITEM('',(#7542),#23);
+#112=STYLED_ITEM('',(#7542),#27);
+#113=STYLED_ITEM('',(#7542),#29);
+#114=STYLED_ITEM('',(#7542),#32);
+#115=STYLED_ITEM('',(#7542),#34);
+#116=STYLED_ITEM('',(#7542),#39);
+#117=STYLED_ITEM('',(#7542),#40);
+#118=STYLED_ITEM('',(#7542),#45);
+#119=STYLED_ITEM('',(#7542),#47);
+#120=STYLED_ITEM('',(#7542),#51);
+#121=STYLED_ITEM('',(#7542),#53);
+#122=STYLED_ITEM('',(#7542),#57);
+#123=STYLED_ITEM('',(#7542),#59);
+#124=STYLED_ITEM('',(#7542),#62);
+#125=STYLED_ITEM('',(#7542),#64);
+#126=STYLED_ITEM('',(#7542),#66);
+#127=STYLED_ITEM('',(#7542),#73);
+#128=STYLED_ITEM('',(#7542),#74);
+#129=STYLED_ITEM('',(#7542),#77);
+#130=STYLED_ITEM('',(#7542),#79);
+#131=STYLED_ITEM('',(#7542),#81);
+#132=STYLED_ITEM('',(#7542),#83);
+#133=STYLED_ITEM('',(#7542),#85);
+#134=STYLED_ITEM('',(#7542),#87);
+#135=STYLED_ITEM('',(#7542),#89);
+#136=STYLED_ITEM('',(#7542),#91);
+#137=STYLED_ITEM('',(#7542),#93);
+#138=STYLED_ITEM('',(#7542),#95);
+#139=MANIFOLD_SOLID_BREP('Volumenk\X\F6rper1',#3582);
+#140=TOROIDAL_SURFACE('',#3707,4.,2.);
+#141=TOROIDAL_SURFACE('',#3726,8.,2.);
+#142=TOROIDAL_SURFACE('',#3732,3.99999999999999,1.99999999999999);
+#143=TOROIDAL_SURFACE('',#3738,8.,2.);
+#144=TOROIDAL_SURFACE('',#3741,173.,2.);
+#145=TOROIDAL_SURFACE('',#3753,3.99999999999997,1.99999999999997);
+#146=TOROIDAL_SURFACE('',#3758,173.,2.);
+#147=TOROIDAL_SURFACE('',#3761,8.,2.);
+#148=TOROIDAL_SURFACE('',#3766,8.,2.);
+#149=TOROIDAL_SURFACE('',#3769,177.000000000002,2.);
+#150=TOROIDAL_SURFACE('',#3801,6.,3.);
+#151=TOROIDAL_SURFACE('',#3816,6.,3.);
+#152=SPHERICAL_SURFACE('',#3688,1.99999999999999);
+#153=SPHERICAL_SURFACE('',#3696,2.);
+#154=SPHERICAL_SURFACE('',#3743,2.);
+#155=SPHERICAL_SURFACE('',#3748,2.);
+#156=(
+BOUNDED_SURFACE()
+B_SPLINE_SURFACE(2,2,((#5395,#5396,#5397,#5398,#5399,#5400,#5401,#5402,
+#5403),(#5404,#5405,#5406,#5407,#5408,#5409,#5410,#5411,#5412),(#5413,#5414,
+#5415,#5416,#5417,#5418,#5419,#5420,#5421)),.UNSPECIFIED.,.F.,.F.,.F.)
+B_SPLINE_SURFACE_WITH_KNOTS((3,3),(3,2,2,2,3),(-0.50536051028416,7.40148683083437E-16),
+(-5.56889075254734,-4.35524170306857,-3.14159265358979,-1.92794360411102,
+-0.714294554632245),.UNSPECIFIED.)
+GEOMETRIC_REPRESENTATION_ITEM()
+RATIONAL_B_SPLINE_SURFACE(((1.,0.821463008719823,1.,0.821463008719823,1.,
+0.821463008719823,1.,0.821463008719823,1.),(0.968245836551949,0.795378138074406,
+0.968245836551949,0.795378138074406,0.968245836551949,0.795378138074406,
+0.968245836551949,0.795378138074406,0.968245836551949),(1.,0.821463008719823,
+1.,0.821463008719823,1.,0.821463008719823,1.,0.821463008719823,1.)))
+REPRESENTATION_ITEM('')
+SURFACE()
+);
+#157=(
+BOUNDED_SURFACE()
+B_SPLINE_SURFACE(2,2,((#6480,#6481,#6482,#6483,#6484,#6485,#6486,#6487,
+#6488),(#6489,#6490,#6491,#6492,#6493,#6494,#6495,#6496,#6497),(#6498,#6499,
+#6500,#6501,#6502,#6503,#6504,#6505,#6506)),.UNSPECIFIED.,.F.,.T.,.F.)
+B_SPLINE_SURFACE_WITH_KNOTS((3,3),(3,2,2,2,3),(-0.505360510284162,0.),(-3.14159265358979,
+-1.5707963267949,0.,1.5707963267949,3.14159265358979),.UNSPECIFIED.)
+GEOMETRIC_REPRESENTATION_ITEM()
+RATIONAL_B_SPLINE_SURFACE(((1.,0.707106781186548,1.,0.707106781186548,1.,
+0.707106781186548,1.,0.707106781186548,1.),(0.96824583655193,0.684653196881511,
+0.96824583655193,0.684653196881511,0.96824583655193,0.684653196881511,0.96824583655193,
+0.684653196881511,0.96824583655193),(1.,0.707106781186548,1.,0.707106781186548,
+1.,0.707106781186548,1.,0.707106781186548,1.)))
+REPRESENTATION_ITEM('')
+SURFACE()
+);
+#158=CYLINDRICAL_SURFACE('',#3611,3.75);
+#159=CYLINDRICAL_SURFACE('',#3639,2.75);
+#160=CYLINDRICAL_SURFACE('',#3643,2.75);
+#161=CYLINDRICAL_SURFACE('',#3648,8.5);
+#162=CYLINDRICAL_SURFACE('',#3651,8.5);
+#163=CYLINDRICAL_SURFACE('',#3692,2.);
+#164=CYLINDRICAL_SURFACE('',#3694,2.);
+#165=CYLINDRICAL_SURFACE('',#3700,2.);
+#166=CYLINDRICAL_SURFACE('',#3702,2.);
+#167=CYLINDRICAL_SURFACE('',#3703,2.);
+#168=CYLINDRICAL_SURFACE('',#3720,2.);
+#169=CYLINDRICAL_SURFACE('',#3721,2.);
+#170=CYLINDRICAL_SURFACE('',#3723,2.);
+#171=CYLINDRICAL_SURFACE('',#3729,10.);
+#172=CYLINDRICAL_SURFACE('',#3736,2.);
+#173=CYLINDRICAL_SURFACE('',#3747,2.);
+#174=CYLINDRICAL_SURFACE('',#3752,2.);
+#175=CYLINDRICAL_SURFACE('',#3757,2.);
+#176=CYLINDRICAL_SURFACE('',#3764,2.);
+#177=CYLINDRICAL_SURFACE('',#3771,2.);
+#178=CYLINDRICAL_SURFACE('',#3772,2.);
+#179=CYLINDRICAL_SURFACE('',#3773,2.);
+#180=CYLINDRICAL_SURFACE('',#3774,2.);
+#181=CYLINDRICAL_SURFACE('',#3775,10.);
+#182=CYLINDRICAL_SURFACE('',#3777,175.);
+#183=CYLINDRICAL_SURFACE('',#3781,1.5);
+#184=CYLINDRICAL_SURFACE('',#3785,1.5);
+#185=CYLINDRICAL_SURFACE('',#3788,1.5);
+#186=CYLINDRICAL_SURFACE('',#3792,1.5);
+#187=CYLINDRICAL_SURFACE('',#3797,3.);
+#188=CYLINDRICAL_SURFACE('',#3799,3.75);
+#189=CYLINDRICAL_SURFACE('',#3807,3.);
+#190=CYLINDRICAL_SURFACE('',#3809,3.75);
+#191=CYLINDRICAL_SURFACE('',#3812,3.);
+#192=CYLINDRICAL_SURFACE('',#3814,3.75);
+#193=CYLINDRICAL_SURFACE('',#3818,3.);
+#194=CYLINDRICAL_SURFACE('',#3823,2.75);
+#195=CYLINDRICAL_SURFACE('',#3826,2.75);
+#196=CYLINDRICAL_SURFACE('',#3829,2.75);
+#197=CYLINDRICAL_SURFACE('',#3832,2.75);
+#198=CYLINDRICAL_SURFACE('',#3880,1.45);
+#199=CYLINDRICAL_SURFACE('',#3884,1.45);
+#200=CYLINDRICAL_SURFACE('',#3888,1.45);
+#201=CYLINDRICAL_SURFACE('',#3892,1.45);
+#202=CYLINDRICAL_SURFACE('',#3896,1.45);
+#203=CYLINDRICAL_SURFACE('',#3900,5.);
+#204=CYLINDRICAL_SURFACE('',#3902,5.);
+#205=CYLINDRICAL_SURFACE('',#3903,5.);
+#206=CYLINDRICAL_SURFACE('',#3907,5.);
+#207=CYLINDRICAL_SURFACE('',#3908,5.);
+#208=CYLINDRICAL_SURFACE('',#3910,5.);
+#209=CYLINDRICAL_SURFACE('',#3912,5.);
+#210=CYLINDRICAL_SURFACE('',#3915,7.);
+#211=CYLINDRICAL_SURFACE('',#3917,7.);
+#212=CYLINDRICAL_SURFACE('',#3919,10.);
+#213=CYLINDRICAL_SURFACE('',#3920,7.);
+#214=CYLINDRICAL_SURFACE('',#3922,7.);
+#215=CYLINDRICAL_SURFACE('',#3930,10.);
+#216=CYLINDRICAL_SURFACE('',#3931,178.000000000002);
+#217=CYLINDRICAL_SURFACE('',#3932,172.);
+#218=CYLINDRICAL_SURFACE('',#3936,172.);
+#219=CYLINDRICAL_SURFACE('',#3938,175.000000000002);
+#220=CYLINDRICAL_SURFACE('',#3940,175.);
+#221=FACE_BOUND('',#1170,.T.);
+#222=FACE_BOUND('',#1204,.T.);
+#223=FACE_BOUND('',#1205,.T.);
+#224=FACE_BOUND('',#1206,.T.);
+#225=FACE_BOUND('',#1207,.T.);
+#226=FACE_BOUND('',#1221,.T.);
+#227=FACE_BOUND('',#1222,.T.);
+#228=FACE_BOUND('',#1223,.T.);
+#229=FACE_BOUND('',#1224,.T.);
+#230=FACE_BOUND('',#1225,.T.);
+#231=FACE_BOUND('',#1255,.T.);
+#232=FACE_BOUND('',#1256,.T.);
+#233=FACE_BOUND('',#1281,.T.);
+#234=FACE_BOUND('',#1283,.T.);
+#235=FACE_BOUND('',#1285,.T.);
+#236=FACE_BOUND('',#1364,.T.);
+#237=FACE_BOUND('',#1365,.T.);
+#238=FACE_BOUND('',#1366,.T.);
+#239=FACE_BOUND('',#1367,.T.);
+#240=FACE_BOUND('',#1368,.T.);
+#241=FACE_BOUND('',#1369,.T.);
+#242=FACE_BOUND('',#1370,.T.);
+#243=FACE_BOUND('',#1371,.T.);
+#244=FACE_BOUND('',#1372,.T.);
+#245=FACE_BOUND('',#1373,.T.);
+#246=FACE_BOUND('',#1374,.T.);
+#247=FACE_BOUND('',#1375,.T.);
+#248=FACE_BOUND('',#1376,.T.);
+#249=FACE_BOUND('',#1377,.T.);
+#250=FACE_BOUND('',#1378,.T.);
+#251=FACE_BOUND('',#1379,.T.);
+#252=FACE_BOUND('',#1380,.T.);
+#253=FACE_BOUND('',#1381,.T.);
+#254=FACE_BOUND('',#1382,.T.);
+#255=FACE_BOUND('',#1383,.T.);
+#256=FACE_BOUND('',#1384,.T.);
+#257=FACE_BOUND('',#1385,.T.);
+#258=FACE_BOUND('',#1386,.T.);
+#259=FACE_BOUND('',#1387,.T.);
+#260=LINE('',#5343,#560);
+#261=LINE('',#5363,#561);
+#262=LINE('',#5365,#562);
+#263=LINE('',#5367,#563);
+#264=LINE('',#5387,#564);
+#265=LINE('',#5388,#565);
+#266=LINE('',#5426,#566);
+#267=LINE('',#5428,#567);
+#268=LINE('',#5430,#568);
+#269=LINE('',#5431,#569);
+#270=LINE('',#5434,#570);
+#271=LINE('',#5436,#571);
+#272=LINE('',#5437,#572);
+#273=LINE('',#5440,#573);
+#274=LINE('',#5442,#574);
+#275=LINE('',#5443,#575);
+#276=LINE('',#5445,#576);
+#277=LINE('',#5446,#577);
+#278=LINE('',#5451,#578);
+#279=LINE('',#5453,#579);
+#280=LINE('',#5455,#580);
+#281=LINE('',#5456,#581);
+#282=LINE('',#5459,#582);
+#283=LINE('',#5461,#583);
+#284=LINE('',#5462,#584);
+#285=LINE('',#5465,#585);
+#286=LINE('',#5467,#586);
+#287=LINE('',#5468,#587);
+#288=LINE('',#5470,#588);
+#289=LINE('',#5471,#589);
+#290=LINE('',#5476,#590);
+#291=LINE('',#5478,#591);
+#292=LINE('',#5480,#592);
+#293=LINE('',#5481,#593);
+#294=LINE('',#5484,#594);
+#295=LINE('',#5486,#595);
+#296=LINE('',#5487,#596);
+#297=LINE('',#5490,#597);
+#298=LINE('',#5492,#598);
+#299=LINE('',#5493,#599);
+#300=LINE('',#5495,#600);
+#301=LINE('',#5496,#601);
+#302=LINE('',#5501,#602);
+#303=LINE('',#5503,#603);
+#304=LINE('',#5505,#604);
+#305=LINE('',#5506,#605);
+#306=LINE('',#5509,#606);
+#307=LINE('',#5511,#607);
+#308=LINE('',#5512,#608);
+#309=LINE('',#5515,#609);
+#310=LINE('',#5517,#610);
+#311=LINE('',#5518,#611);
+#312=LINE('',#5520,#612);
+#313=LINE('',#5521,#613);
+#314=LINE('',#5526,#614);
+#315=LINE('',#5528,#615);
+#316=LINE('',#5530,#616);
+#317=LINE('',#5531,#617);
+#318=LINE('',#5534,#618);
+#319=LINE('',#5536,#619);
+#320=LINE('',#5537,#620);
+#321=LINE('',#5540,#621);
+#322=LINE('',#5542,#622);
+#323=LINE('',#5543,#623);
+#324=LINE('',#5545,#624);
+#325=LINE('',#5546,#625);
+#326=LINE('',#5552,#626);
+#327=LINE('',#5571,#627);
+#328=LINE('',#5588,#628);
+#329=LINE('',#5599,#629);
+#330=LINE('',#5610,#630);
+#331=LINE('',#5612,#631);
+#332=LINE('',#5614,#632);
+#333=LINE('',#5615,#633);
+#334=LINE('',#5619,#634);
+#335=LINE('',#5623,#635);
+#336=LINE('',#5628,#636);
+#337=LINE('',#5632,#637);
+#338=LINE('',#5636,#638);
+#339=LINE('',#5638,#639);
+#340=LINE('',#5644,#640);
+#341=LINE('',#5660,#641);
+#342=LINE('',#5666,#642);
+#343=LINE('',#5667,#643);
+#344=LINE('',#5669,#644);
+#345=LINE('',#5673,#645);
+#346=LINE('',#5685,#646);
+#347=LINE('',#5697,#647);
+#348=LINE('',#5709,#648);
+#349=LINE('',#5712,#649);
+#350=LINE('',#5723,#650);
+#351=LINE('',#5725,#651);
+#352=LINE('',#5726,#652);
+#353=LINE('',#5727,#653);
+#354=LINE('',#5737,#654);
+#355=LINE('',#5938,#655);
+#356=LINE('',#5939,#656);
+#357=LINE('',#5948,#657);
+#358=LINE('',#6122,#658);
+#359=LINE('',#6127,#659);
+#360=LINE('',#6128,#660);
+#361=LINE('',#6133,#661);
+#362=LINE('',#6134,#662);
+#363=LINE('',#6145,#663);
+#364=LINE('',#6160,#664);
+#365=LINE('',#6168,#665);
+#366=LINE('',#6170,#666);
+#367=LINE('',#6172,#667);
+#368=LINE('',#6179,#668);
+#369=LINE('',#6182,#669);
+#370=LINE('',#6184,#670);
+#371=LINE('',#6186,#671);
+#372=LINE('',#6187,#672);
+#373=LINE('',#6190,#673);
+#374=LINE('',#6192,#674);
+#375=LINE('',#6194,#675);
+#376=LINE('',#6195,#676);
+#377=LINE('',#6198,#677);
+#378=LINE('',#6200,#678);
+#379=LINE('',#6202,#679);
+#380=LINE('',#6203,#680);
+#381=LINE('',#6206,#681);
+#382=LINE('',#6208,#682);
+#383=LINE('',#6210,#683);
+#384=LINE('',#6211,#684);
+#385=LINE('',#6214,#685);
+#386=LINE('',#6216,#686);
+#387=LINE('',#6218,#687);
+#388=LINE('',#6219,#688);
+#389=LINE('',#6223,#689);
+#390=LINE('',#6230,#690);
+#391=LINE('',#6233,#691);
+#392=LINE('',#6281,#692);
+#393=LINE('',#6283,#693);
+#394=LINE('',#6286,#694);
+#395=LINE('',#6287,#695);
+#396=LINE('',#6297,#696);
+#397=LINE('',#6310,#697);
+#398=LINE('',#6324,#698);
+#399=LINE('',#6336,#699);
+#400=LINE('',#6344,#700);
+#401=LINE('',#6345,#701);
+#402=LINE('',#6347,#702);
+#403=LINE('',#6349,#703);
+#404=LINE('',#6351,#704);
+#405=LINE('',#6352,#705);
+#406=LINE('',#6354,#706);
+#407=LINE('',#6356,#707);
+#408=LINE('',#6359,#708);
+#409=LINE('',#6360,#709);
+#410=LINE('',#6363,#710);
+#411=LINE('',#6365,#711);
+#412=LINE('',#6366,#712);
+#413=LINE('',#6372,#713);
+#414=LINE('',#6377,#714);
+#415=LINE('',#6384,#715);
+#416=LINE('',#6391,#716);
+#417=LINE('',#6468,#717);
+#418=LINE('',#6472,#718);
+#419=LINE('',#6512,#719);
+#420=LINE('',#6517,#720);
+#421=LINE('',#6954,#721);
+#422=LINE('',#6959,#722);
+#423=LINE('',#6969,#723);
+#424=LINE('',#6974,#724);
+#425=LINE('',#6979,#725);
+#426=LINE('',#6984,#726);
+#427=LINE('',#6989,#727);
+#428=LINE('',#6991,#728);
+#429=LINE('',#6992,#729);
+#430=LINE('',#6995,#730);
+#431=LINE('',#6996,#731);
+#432=LINE('',#6999,#732);
+#433=LINE('',#7000,#733);
+#434=LINE('',#7002,#734);
+#435=LINE('',#7005,#735);
+#436=LINE('',#7007,#736);
+#437=LINE('',#7008,#737);
+#438=LINE('',#7011,#738);
+#439=LINE('',#7012,#739);
+#440=LINE('',#7015,#740);
+#441=LINE('',#7016,#741);
+#442=LINE('',#7018,#742);
+#443=LINE('',#7021,#743);
+#444=LINE('',#7023,#744);
+#445=LINE('',#7024,#745);
+#446=LINE('',#7027,#746);
+#447=LINE('',#7028,#747);
+#448=LINE('',#7031,#748);
+#449=LINE('',#7032,#749);
+#450=LINE('',#7034,#750);
+#451=LINE('',#7037,#751);
+#452=LINE('',#7039,#752);
+#453=LINE('',#7040,#753);
+#454=LINE('',#7043,#754);
+#455=LINE('',#7044,#755);
+#456=LINE('',#7047,#756);
+#457=LINE('',#7048,#757);
+#458=LINE('',#7050,#758);
+#459=LINE('',#7053,#759);
+#460=LINE('',#7055,#760);
+#461=LINE('',#7056,#761);
+#462=LINE('',#7059,#762);
+#463=LINE('',#7060,#763);
+#464=LINE('',#7063,#764);
+#465=LINE('',#7064,#765);
+#466=LINE('',#7066,#766);
+#467=LINE('',#7070,#767);
+#468=LINE('',#7072,#768);
+#469=LINE('',#7074,#769);
+#470=LINE('',#7075,#770);
+#471=LINE('',#7078,#771);
+#472=LINE('',#7080,#772);
+#473=LINE('',#7081,#773);
+#474=LINE('',#7084,#774);
+#475=LINE('',#7086,#775);
+#476=LINE('',#7087,#776);
+#477=LINE('',#7089,#777);
+#478=LINE('',#7090,#778);
+#479=LINE('',#7095,#779);
+#480=LINE('',#7097,#780);
+#481=LINE('',#7099,#781);
+#482=LINE('',#7100,#782);
+#483=LINE('',#7103,#783);
+#484=LINE('',#7105,#784);
+#485=LINE('',#7106,#785);
+#486=LINE('',#7109,#786);
+#487=LINE('',#7111,#787);
+#488=LINE('',#7112,#788);
+#489=LINE('',#7114,#789);
+#490=LINE('',#7115,#790);
+#491=LINE('',#7120,#791);
+#492=LINE('',#7122,#792);
+#493=LINE('',#7124,#793);
+#494=LINE('',#7125,#794);
+#495=LINE('',#7128,#795);
+#496=LINE('',#7130,#796);
+#497=LINE('',#7131,#797);
+#498=LINE('',#7134,#798);
+#499=LINE('',#7136,#799);
+#500=LINE('',#7137,#800);
+#501=LINE('',#7139,#801);
+#502=LINE('',#7140,#802);
+#503=LINE('',#7145,#803);
+#504=LINE('',#7147,#804);
+#505=LINE('',#7149,#805);
+#506=LINE('',#7150,#806);
+#507=LINE('',#7153,#807);
+#508=LINE('',#7155,#808);
+#509=LINE('',#7156,#809);
+#510=LINE('',#7159,#810);
+#511=LINE('',#7161,#811);
+#512=LINE('',#7162,#812);
+#513=LINE('',#7164,#813);
+#514=LINE('',#7165,#814);
+#515=LINE('',#7170,#815);
+#516=LINE('',#7172,#816);
+#517=LINE('',#7174,#817);
+#518=LINE('',#7175,#818);
+#519=LINE('',#7178,#819);
+#520=LINE('',#7180,#820);
+#521=LINE('',#7181,#821);
+#522=LINE('',#7184,#822);
+#523=LINE('',#7186,#823);
+#524=LINE('',#7187,#824);
+#525=LINE('',#7189,#825);
+#526=LINE('',#7190,#826);
+#527=LINE('',#7196,#827);
+#528=LINE('',#7203,#828);
+#529=LINE('',#7210,#829);
+#530=LINE('',#7217,#830);
+#531=LINE('',#7224,#831);
+#532=LINE('',#7229,#832);
+#533=LINE('',#7231,#833);
+#534=LINE('',#7236,#834);
+#535=LINE('',#7239,#835);
+#536=LINE('',#7245,#836);
+#537=LINE('',#7248,#837);
+#538=LINE('',#7251,#838);
+#539=LINE('',#7253,#839);
+#540=LINE('',#7257,#840);
+#541=LINE('',#7260,#841);
+#542=LINE('',#7263,#842);
+#543=LINE('',#7264,#843);
+#544=LINE('',#7268,#844);
+#545=LINE('',#7271,#845);
+#546=LINE('',#7274,#846);
+#547=LINE('',#7275,#847);
+#548=LINE('',#7279,#848);
+#549=LINE('',#7286,#849);
+#550=LINE('',#7288,#850);
+#551=LINE('',#7290,#851);
+#552=LINE('',#7292,#852);
+#553=LINE('',#7296,#853);
+#554=LINE('',#7298,#854);
+#555=LINE('',#7299,#855);
+#556=LINE('',#7302,#856);
+#557=LINE('',#7304,#857);
+#558=LINE('',#7306,#858);
+#559=LINE('',#7308,#859);
+#560=VECTOR('',#3974,10.);
+#561=VECTOR('',#3975,10.);
+#562=VECTOR('',#3976,10.);
+#563=VECTOR('',#3977,10.);
+#564=VECTOR('',#3978,10.);
+#565=VECTOR('',#3979,10.);
+#566=VECTOR('',#3994,10.);
+#567=VECTOR('',#3995,10.);
+#568=VECTOR('',#3996,10.);
+#569=VECTOR('',#3997,10.);
+#570=VECTOR('',#4000,10.);
+#571=VECTOR('',#4001,10.);
+#572=VECTOR('',#4002,10.);
+#573=VECTOR('',#4005,10.);
+#574=VECTOR('',#4006,10.);
+#575=VECTOR('',#4007,10.);
+#576=VECTOR('',#4010,10.);
+#577=VECTOR('',#4011,10.);
+#578=VECTOR('',#4016,10.);
+#579=VECTOR('',#4017,10.);
+#580=VECTOR('',#4018,10.);
+#581=VECTOR('',#4019,10.);
+#582=VECTOR('',#4022,10.);
+#583=VECTOR('',#4023,10.);
+#584=VECTOR('',#4024,10.);
+#585=VECTOR('',#4027,10.);
+#586=VECTOR('',#4028,10.);
+#587=VECTOR('',#4029,10.);
+#588=VECTOR('',#4032,10.);
+#589=VECTOR('',#4033,10.);
+#590=VECTOR('',#4038,10.);
+#591=VECTOR('',#4039,10.);
+#592=VECTOR('',#4040,10.);
+#593=VECTOR('',#4041,10.);
+#594=VECTOR('',#4044,10.);
+#595=VECTOR('',#4045,10.);
+#596=VECTOR('',#4046,10.);
+#597=VECTOR('',#4049,10.);
+#598=VECTOR('',#4050,10.);
+#599=VECTOR('',#4051,10.);
+#600=VECTOR('',#4054,10.);
+#601=VECTOR('',#4055,10.);
+#602=VECTOR('',#4060,10.);
+#603=VECTOR('',#4061,10.);
+#604=VECTOR('',#4062,10.);
+#605=VECTOR('',#4063,10.);
+#606=VECTOR('',#4066,10.);
+#607=VECTOR('',#4067,10.);
+#608=VECTOR('',#4068,10.);
+#609=VECTOR('',#4071,10.);
+#610=VECTOR('',#4072,10.);
+#611=VECTOR('',#4073,10.);
+#612=VECTOR('',#4076,10.);
+#613=VECTOR('',#4077,10.);
+#614=VECTOR('',#4082,10.);
+#615=VECTOR('',#4083,10.);
+#616=VECTOR('',#4084,10.);
+#617=VECTOR('',#4085,10.);
+#618=VECTOR('',#4088,10.);
+#619=VECTOR('',#4089,10.);
+#620=VECTOR('',#4090,10.);
+#621=VECTOR('',#4093,10.);
+#622=VECTOR('',#4094,10.);
+#623=VECTOR('',#4095,10.);
+#624=VECTOR('',#4098,10.);
+#625=VECTOR('',#4099,10.);
+#626=VECTOR('',#4106,2.75);
+#627=VECTOR('',#4115,2.75);
+#628=VECTOR('',#4122,10.);
+#629=VECTOR('',#4123,10.);
+#630=VECTOR('',#4124,10.);
+#631=VECTOR('',#4125,10.);
+#632=VECTOR('',#4126,10.);
+#633=VECTOR('',#4127,10.);
+#634=VECTOR('',#4130,10.);
+#635=VECTOR('',#4133,10.);
+#636=VECTOR('',#4138,10.);
+#637=VECTOR('',#4141,10.);
+#638=VECTOR('',#4146,10.);
+#639=VECTOR('',#4147,10.);
+#640=VECTOR('',#4152,10.);
+#641=VECTOR('',#4167,10.);
+#642=VECTOR('',#4172,10.);
+#643=VECTOR('',#4173,10.);
+#644=VECTOR('',#4174,10.);
+#645=VECTOR('',#4177,10.);
+#646=VECTOR('',#4188,10.);
+#647=VECTOR('',#4199,10.);
+#648=VECTOR('',#4210,10.);
+#649=VECTOR('',#4213,10.);
+#650=VECTOR('',#4224,10.);
+#651=VECTOR('',#4225,10.);
+#652=VECTOR('',#4226,10.);
+#653=VECTOR('',#4227,10.);
+#654=VECTOR('',#4240,10.);
+#655=VECTOR('',#4245,10.);
+#656=VECTOR('',#4246,10.);
+#657=VECTOR('',#4257,10.);
+#658=VECTOR('',#4262,10.);
+#659=VECTOR('',#4267,10.);
+#660=VECTOR('',#4268,10.);
+#661=VECTOR('',#4273,10.);
+#662=VECTOR('',#4274,10.);
+#663=VECTOR('',#4283,2.);
+#664=VECTOR('',#4290,10.);
+#665=VECTOR('',#4297,10.);
+#666=VECTOR('',#4298,10.);
+#667=VECTOR('',#4299,10.);
+#668=VECTOR('',#4306,10.);
+#669=VECTOR('',#4307,10.);
+#670=VECTOR('',#4308,10.);
+#671=VECTOR('',#4309,10.);
+#672=VECTOR('',#4310,10.);
+#673=VECTOR('',#4311,10.);
+#674=VECTOR('',#4312,10.);
+#675=VECTOR('',#4313,10.);
+#676=VECTOR('',#4314,10.);
+#677=VECTOR('',#4315,10.);
+#678=VECTOR('',#4316,10.);
+#679=VECTOR('',#4317,10.);
+#680=VECTOR('',#4318,10.);
+#681=VECTOR('',#4319,10.);
+#682=VECTOR('',#4320,10.);
+#683=VECTOR('',#4321,10.);
+#684=VECTOR('',#4322,10.);
+#685=VECTOR('',#4323,10.);
+#686=VECTOR('',#4324,10.);
+#687=VECTOR('',#4325,10.);
+#688=VECTOR('',#4326,10.);
+#689=VECTOR('',#4331,10.);
+#690=VECTOR('',#4338,2.);
+#691=VECTOR('',#4341,2.);
+#692=VECTOR('',#4352,10.);
+#693=VECTOR('',#4353,10.);
+#694=VECTOR('',#4356,10.);
+#695=VECTOR('',#4357,10.);
+#696=VECTOR('',#4370,10.);
+#697=VECTOR('',#4391,10.);
+#698=VECTOR('',#4412,10.);
+#699=VECTOR('',#4429,10.);
+#700=VECTOR('',#4442,10.);
+#701=VECTOR('',#4443,10.);
+#702=VECTOR('',#4446,10.);
+#703=VECTOR('',#4449,10.);
+#704=VECTOR('',#4452,10.);
+#705=VECTOR('',#4453,10.);
+#706=VECTOR('',#4456,10.);
+#707=VECTOR('',#4457,10.);
+#708=VECTOR('',#4460,10.);
+#709=VECTOR('',#4461,10.);
+#710=VECTOR('',#4466,10.);
+#711=VECTOR('',#4469,10.);
+#712=VECTOR('',#4470,10.);
+#713=VECTOR('',#4477,1.5);
+#714=VECTOR('',#4484,1.5);
+#715=VECTOR('',#4493,1.5);
+#716=VECTOR('',#4502,1.5);
+#717=VECTOR('',#4511,3.);
+#718=VECTOR('',#4516,3.75);
+#719=VECTOR('',#4533,3.);
+#720=VECTOR('',#4540,3.75);
+#721=VECTOR('',#4545,3.);
+#722=VECTOR('',#4552,3.75);
+#723=VECTOR('',#4569,2.75);
+#724=VECTOR('',#4576,2.75);
+#725=VECTOR('',#4583,2.75);
+#726=VECTOR('',#4590,2.75);
+#727=VECTOR('',#4597,10.);
+#728=VECTOR('',#4598,10.);
+#729=VECTOR('',#4599,10.);
+#730=VECTOR('',#4602,10.);
+#731=VECTOR('',#4603,10.);
+#732=VECTOR('',#4606,10.);
+#733=VECTOR('',#4607,10.);
+#734=VECTOR('',#4610,10.);
+#735=VECTOR('',#4613,10.);
+#736=VECTOR('',#4614,10.);
+#737=VECTOR('',#4615,10.);
+#738=VECTOR('',#4618,10.);
+#739=VECTOR('',#4619,10.);
+#740=VECTOR('',#4622,10.);
+#741=VECTOR('',#4623,10.);
+#742=VECTOR('',#4626,10.);
+#743=VECTOR('',#4629,10.);
+#744=VECTOR('',#4630,10.);
+#745=VECTOR('',#4631,10.);
+#746=VECTOR('',#4634,10.);
+#747=VECTOR('',#4635,10.);
+#748=VECTOR('',#4638,10.);
+#749=VECTOR('',#4639,10.);
+#750=VECTOR('',#4642,10.);
+#751=VECTOR('',#4645,10.);
+#752=VECTOR('',#4646,10.);
+#753=VECTOR('',#4647,10.);
+#754=VECTOR('',#4650,10.);
+#755=VECTOR('',#4651,10.);
+#756=VECTOR('',#4654,10.);
+#757=VECTOR('',#4655,10.);
+#758=VECTOR('',#4658,10.);
+#759=VECTOR('',#4661,10.);
+#760=VECTOR('',#4662,10.);
+#761=VECTOR('',#4663,10.);
+#762=VECTOR('',#4666,10.);
+#763=VECTOR('',#4667,10.);
+#764=VECTOR('',#4670,10.);
+#765=VECTOR('',#4671,10.);
+#766=VECTOR('',#4674,10.);
+#767=VECTOR('',#4677,10.);
+#768=VECTOR('',#4678,10.);
+#769=VECTOR('',#4679,10.);
+#770=VECTOR('',#4680,10.);
+#771=VECTOR('',#4683,10.);
+#772=VECTOR('',#4684,10.);
+#773=VECTOR('',#4685,10.);
+#774=VECTOR('',#4688,10.);
+#775=VECTOR('',#4689,10.);
+#776=VECTOR('',#4690,10.);
+#777=VECTOR('',#4693,10.);
+#778=VECTOR('',#4694,10.);
+#779=VECTOR('',#4699,10.);
+#780=VECTOR('',#4700,10.);
+#781=VECTOR('',#4701,10.);
+#782=VECTOR('',#4702,10.);
+#783=VECTOR('',#4705,10.);
+#784=VECTOR('',#4706,10.);
+#785=VECTOR('',#4707,10.);
+#786=VECTOR('',#4710,10.);
+#787=VECTOR('',#4711,10.);
+#788=VECTOR('',#4712,10.);
+#789=VECTOR('',#4715,10.);
+#790=VECTOR('',#4716,10.);
+#791=VECTOR('',#4721,10.);
+#792=VECTOR('',#4722,10.);
+#793=VECTOR('',#4723,10.);
+#794=VECTOR('',#4724,10.);
+#795=VECTOR('',#4727,10.);
+#796=VECTOR('',#4728,10.);
+#797=VECTOR('',#4729,10.);
+#798=VECTOR('',#4732,10.);
+#799=VECTOR('',#4733,10.);
+#800=VECTOR('',#4734,10.);
+#801=VECTOR('',#4737,10.);
+#802=VECTOR('',#4738,10.);
+#803=VECTOR('',#4743,10.);
+#804=VECTOR('',#4744,10.);
+#805=VECTOR('',#4745,10.);
+#806=VECTOR('',#4746,10.);
+#807=VECTOR('',#4749,10.);
+#808=VECTOR('',#4750,10.);
+#809=VECTOR('',#4751,10.);
+#810=VECTOR('',#4754,10.);
+#811=VECTOR('',#4755,10.);
+#812=VECTOR('',#4756,10.);
+#813=VECTOR('',#4759,10.);
+#814=VECTOR('',#4760,10.);
+#815=VECTOR('',#4765,10.);
+#816=VECTOR('',#4766,10.);
+#817=VECTOR('',#4767,10.);
+#818=VECTOR('',#4768,10.);
+#819=VECTOR('',#4771,10.);
+#820=VECTOR('',#4772,10.);
+#821=VECTOR('',#4773,10.);
+#822=VECTOR('',#4776,10.);
+#823=VECTOR('',#4777,10.);
+#824=VECTOR('',#4778,10.);
+#825=VECTOR('',#4781,10.);
+#826=VECTOR('',#4782,10.);
+#827=VECTOR('',#4789,1.45);
+#828=VECTOR('',#4798,1.45);
+#829=VECTOR('',#4807,1.45);
+#830=VECTOR('',#4816,1.45);
+#831=VECTOR('',#4825,1.45);
+#832=VECTOR('',#4832,10.);
+#833=VECTOR('',#4833,10.);
+#834=VECTOR('',#4840,10.);
+#835=VECTOR('',#4843,10.);
+#836=VECTOR('',#4852,10.);
+#837=VECTOR('',#4855,10.);
+#838=VECTOR('',#4858,10.);
+#839=VECTOR('',#4859,10.);
+#840=VECTOR('',#4864,10.);
+#841=VECTOR('',#4867,10.);
+#842=VECTOR('',#4870,10.);
+#843=VECTOR('',#4871,10.);
+#844=VECTOR('',#4876,10.);
+#845=VECTOR('',#4879,10.);
+#846=VECTOR('',#4884,10.);
+#847=VECTOR('',#4885,10.);
+#848=VECTOR('',#4890,10.);
+#849=VECTOR('',#4899,10.);
+#850=VECTOR('',#4900,10.);
+#851=VECTOR('',#4901,10.);
+#852=VECTOR('',#4904,10.);
+#853=VECTOR('',#4911,10.);
+#854=VECTOR('',#4914,10.);
+#855=VECTOR('',#4915,10.);
+#856=VECTOR('',#4920,10.);
+#857=VECTOR('',#4923,10.);
+#858=VECTOR('',#4926,10.);
+#859=VECTOR('',#4929,10.);
+#860=PLANE('',#3607);
+#861=PLANE('',#3608);
+#862=PLANE('',#3614);
+#863=PLANE('',#3615);
+#864=PLANE('',#3616);
+#865=PLANE('',#3617);
+#866=PLANE('',#3618);
+#867=PLANE('',#3619);
+#868=PLANE('',#3620);
+#869=PLANE('',#3621);
+#870=PLANE('',#3622);
+#871=PLANE('',#3623);
+#872=PLANE('',#3624);
+#873=PLANE('',#3625);
+#874=PLANE('',#3626);
+#875=PLANE('',#3627);
+#876=PLANE('',#3628);
+#877=PLANE('',#3629);
+#878=PLANE('',#3630);
+#879=PLANE('',#3631);
+#880=PLANE('',#3632);
+#881=PLANE('',#3633);
+#882=PLANE('',#3634);
+#883=PLANE('',#3635);
+#884=PLANE('',#3636);
+#885=PLANE('',#3637);
+#886=PLANE('',#3638);
+#887=PLANE('',#3647);
+#888=PLANE('',#3654);
+#889=PLANE('',#3687);
+#890=PLANE('',#3705);
+#891=PLANE('',#3710);
+#892=PLANE('',#3778);
+#893=PLANE('',#3779);
+#894=PLANE('',#3780);
+#895=PLANE('',#3784);
+#896=PLANE('',#3787);
+#897=PLANE('',#3791);
+#898=PLANE('',#3795);
+#899=PLANE('',#3820);
+#900=PLANE('',#3821);
+#901=PLANE('',#3822);
+#902=PLANE('',#3825);
+#903=PLANE('',#3828);
+#904=PLANE('',#3831);
+#905=PLANE('',#3834);
+#906=PLANE('',#3835);
+#907=PLANE('',#3836);
+#908=PLANE('',#3837);
+#909=PLANE('',#3838);
+#910=PLANE('',#3839);
+#911=PLANE('',#3840);
+#912=PLANE('',#3841);
+#913=PLANE('',#3842);
+#914=PLANE('',#3843);
+#915=PLANE('',#3844);
+#916=PLANE('',#3845);
+#917=PLANE('',#3846);
+#918=PLANE('',#3847);
+#919=PLANE('',#3848);
+#920=PLANE('',#3849);
+#921=PLANE('',#3850);
+#922=PLANE('',#3851);
+#923=PLANE('',#3852);
+#924=PLANE('',#3853);
+#925=PLANE('',#3854);
+#926=PLANE('',#3855);
+#927=PLANE('',#3856);
+#928=PLANE('',#3857);
+#929=PLANE('',#3858);
+#930=PLANE('',#3859);
+#931=PLANE('',#3860);
+#932=PLANE('',#3861);
+#933=PLANE('',#3862);
+#934=PLANE('',#3863);
+#935=PLANE('',#3864);
+#936=PLANE('',#3865);
+#937=PLANE('',#3866);
+#938=PLANE('',#3867);
+#939=PLANE('',#3868);
+#940=PLANE('',#3869);
+#941=PLANE('',#3870);
+#942=PLANE('',#3871);
+#943=PLANE('',#3872);
+#944=PLANE('',#3873);
+#945=PLANE('',#3874);
+#946=PLANE('',#3875);
+#947=PLANE('',#3876);
+#948=PLANE('',#3877);
+#949=PLANE('',#3878);
+#950=PLANE('',#3879);
+#951=PLANE('',#3883);
+#952=PLANE('',#3887);
+#953=PLANE('',#3891);
+#954=PLANE('',#3895);
+#955=PLANE('',#3899);
+#956=PLANE('',#3905);
+#957=PLANE('',#3914);
+#958=PLANE('',#3924);
+#959=PLANE('',#3928);
+#960=PLANE('',#3929);
+#961=PLANE('',#3933);
+#962=PLANE('',#3934);
+#963=PLANE('',#3935);
+#964=PLANE('',#3937);
+#965=PLANE('',#3939);
+#966=PLANE('',#3941);
+#967=PLANE('',#3942);
+#968=FACE_OUTER_BOUND('',#1166,.T.);
+#969=FACE_OUTER_BOUND('',#1167,.T.);
+#970=FACE_OUTER_BOUND('',#1168,.T.);
+#971=FACE_OUTER_BOUND('',#1169,.T.);
+#972=FACE_OUTER_BOUND('',#1171,.T.);
+#973=FACE_OUTER_BOUND('',#1172,.T.);
+#974=FACE_OUTER_BOUND('',#1173,.T.);
+#975=FACE_OUTER_BOUND('',#1174,.T.);
+#976=FACE_OUTER_BOUND('',#1175,.T.);
+#977=FACE_OUTER_BOUND('',#1176,.T.);
+#978=FACE_OUTER_BOUND('',#1177,.T.);
+#979=FACE_OUTER_BOUND('',#1178,.T.);
+#980=FACE_OUTER_BOUND('',#1179,.T.);
+#981=FACE_OUTER_BOUND('',#1180,.T.);
+#982=FACE_OUTER_BOUND('',#1181,.T.);
+#983=FACE_OUTER_BOUND('',#1182,.T.);
+#984=FACE_OUTER_BOUND('',#1183,.T.);
+#985=FACE_OUTER_BOUND('',#1184,.T.);
+#986=FACE_OUTER_BOUND('',#1185,.T.);
+#987=FACE_OUTER_BOUND('',#1186,.T.);
+#988=FACE_OUTER_BOUND('',#1187,.T.);
+#989=FACE_OUTER_BOUND('',#1188,.T.);
+#990=FACE_OUTER_BOUND('',#1189,.T.);
+#991=FACE_OUTER_BOUND('',#1190,.T.);
+#992=FACE_OUTER_BOUND('',#1191,.T.);
+#993=FACE_OUTER_BOUND('',#1192,.T.);
+#994=FACE_OUTER_BOUND('',#1193,.T.);
+#995=FACE_OUTER_BOUND('',#1194,.T.);
+#996=FACE_OUTER_BOUND('',#1195,.T.);
+#997=FACE_OUTER_BOUND('',#1196,.T.);
+#998=FACE_OUTER_BOUND('',#1197,.T.);
+#999=FACE_OUTER_BOUND('',#1198,.T.);
+#1000=FACE_OUTER_BOUND('',#1199,.T.);
+#1001=FACE_OUTER_BOUND('',#1200,.T.);
+#1002=FACE_OUTER_BOUND('',#1201,.T.);
+#1003=FACE_OUTER_BOUND('',#1202,.T.);
+#1004=FACE_OUTER_BOUND('',#1203,.T.);
+#1005=FACE_OUTER_BOUND('',#1208,.T.);
+#1006=FACE_OUTER_BOUND('',#1209,.T.);
+#1007=FACE_OUTER_BOUND('',#1210,.T.);
+#1008=FACE_OUTER_BOUND('',#1211,.T.);
+#1009=FACE_OUTER_BOUND('',#1212,.T.);
+#1010=FACE_OUTER_BOUND('',#1213,.T.);
+#1011=FACE_OUTER_BOUND('',#1214,.T.);
+#1012=FACE_OUTER_BOUND('',#1215,.T.);
+#1013=FACE_OUTER_BOUND('',#1216,.T.);
+#1014=FACE_OUTER_BOUND('',#1217,.T.);
+#1015=FACE_OUTER_BOUND('',#1218,.T.);
+#1016=FACE_OUTER_BOUND('',#1219,.T.);
+#1017=FACE_OUTER_BOUND('',#1220,.T.);
+#1018=FACE_OUTER_BOUND('',#1226,.T.);
+#1019=FACE_OUTER_BOUND('',#1227,.T.);
+#1020=FACE_OUTER_BOUND('',#1228,.T.);
+#1021=FACE_OUTER_BOUND('',#1229,.T.);
+#1022=FACE_OUTER_BOUND('',#1230,.T.);
+#1023=FACE_OUTER_BOUND('',#1231,.T.);
+#1024=FACE_OUTER_BOUND('',#1232,.T.);
+#1025=FACE_OUTER_BOUND('',#1233,.T.);
+#1026=FACE_OUTER_BOUND('',#1234,.T.);
+#1027=FACE_OUTER_BOUND('',#1235,.T.);
+#1028=FACE_OUTER_BOUND('',#1236,.T.);
+#1029=FACE_OUTER_BOUND('',#1237,.T.);
+#1030=FACE_OUTER_BOUND('',#1238,.T.);
+#1031=FACE_OUTER_BOUND('',#1239,.T.);
+#1032=FACE_OUTER_BOUND('',#1240,.T.);
+#1033=FACE_OUTER_BOUND('',#1241,.T.);
+#1034=FACE_OUTER_BOUND('',#1242,.T.);
+#1035=FACE_OUTER_BOUND('',#1243,.T.);
+#1036=FACE_OUTER_BOUND('',#1244,.T.);
+#1037=FACE_OUTER_BOUND('',#1245,.T.);
+#1038=FACE_OUTER_BOUND('',#1246,.T.);
+#1039=FACE_OUTER_BOUND('',#1247,.T.);
+#1040=FACE_OUTER_BOUND('',#1248,.T.);
+#1041=FACE_OUTER_BOUND('',#1249,.T.);
+#1042=FACE_OUTER_BOUND('',#1250,.T.);
+#1043=FACE_OUTER_BOUND('',#1251,.T.);
+#1044=FACE_OUTER_BOUND('',#1252,.T.);
+#1045=FACE_OUTER_BOUND('',#1253,.T.);
+#1046=FACE_OUTER_BOUND('',#1254,.T.);
+#1047=FACE_OUTER_BOUND('',#1257,.T.);
+#1048=FACE_OUTER_BOUND('',#1258,.T.);
+#1049=FACE_OUTER_BOUND('',#1259,.T.);
+#1050=FACE_OUTER_BOUND('',#1260,.T.);
+#1051=FACE_OUTER_BOUND('',#1261,.T.);
+#1052=FACE_OUTER_BOUND('',#1262,.T.);
+#1053=FACE_OUTER_BOUND('',#1263,.T.);
+#1054=FACE_OUTER_BOUND('',#1264,.T.);
+#1055=FACE_OUTER_BOUND('',#1265,.T.);
+#1056=FACE_OUTER_BOUND('',#1266,.T.);
+#1057=FACE_OUTER_BOUND('',#1267,.T.);
+#1058=FACE_OUTER_BOUND('',#1268,.T.);
+#1059=FACE_OUTER_BOUND('',#1269,.T.);
+#1060=FACE_OUTER_BOUND('',#1270,.T.);
+#1061=FACE_OUTER_BOUND('',#1271,.T.);
+#1062=FACE_OUTER_BOUND('',#1272,.T.);
+#1063=FACE_OUTER_BOUND('',#1273,.T.);
+#1064=FACE_OUTER_BOUND('',#1274,.T.);
+#1065=FACE_OUTER_BOUND('',#1275,.T.);
+#1066=FACE_OUTER_BOUND('',#1276,.T.);
+#1067=FACE_OUTER_BOUND('',#1277,.T.);
+#1068=FACE_OUTER_BOUND('',#1278,.T.);
+#1069=FACE_OUTER_BOUND('',#1279,.T.);
+#1070=FACE_OUTER_BOUND('',#1280,.T.);
+#1071=FACE_OUTER_BOUND('',#1282,.T.);
+#1072=FACE_OUTER_BOUND('',#1284,.T.);
+#1073=FACE_OUTER_BOUND('',#1286,.T.);
+#1074=FACE_OUTER_BOUND('',#1287,.T.);
+#1075=FACE_OUTER_BOUND('',#1288,.T.);
+#1076=FACE_OUTER_BOUND('',#1289,.T.);
+#1077=FACE_OUTER_BOUND('',#1290,.T.);
+#1078=FACE_OUTER_BOUND('',#1291,.T.);
+#1079=FACE_OUTER_BOUND('',#1292,.T.);
+#1080=FACE_OUTER_BOUND('',#1293,.T.);
+#1081=FACE_OUTER_BOUND('',#1294,.T.);
+#1082=FACE_OUTER_BOUND('',#1295,.T.);
+#1083=FACE_OUTER_BOUND('',#1296,.T.);
+#1084=FACE_OUTER_BOUND('',#1297,.T.);
+#1085=FACE_OUTER_BOUND('',#1298,.T.);
+#1086=FACE_OUTER_BOUND('',#1299,.T.);
+#1087=FACE_OUTER_BOUND('',#1300,.T.);
+#1088=FACE_OUTER_BOUND('',#1301,.T.);
+#1089=FACE_OUTER_BOUND('',#1302,.T.);
+#1090=FACE_OUTER_BOUND('',#1303,.T.);
+#1091=FACE_OUTER_BOUND('',#1304,.T.);
+#1092=FACE_OUTER_BOUND('',#1305,.T.);
+#1093=FACE_OUTER_BOUND('',#1306,.T.);
+#1094=FACE_OUTER_BOUND('',#1307,.T.);
+#1095=FACE_OUTER_BOUND('',#1308,.T.);
+#1096=FACE_OUTER_BOUND('',#1309,.T.);
+#1097=FACE_OUTER_BOUND('',#1310,.T.);
+#1098=FACE_OUTER_BOUND('',#1311,.T.);
+#1099=FACE_OUTER_BOUND('',#1312,.T.);
+#1100=FACE_OUTER_BOUND('',#1313,.T.);
+#1101=FACE_OUTER_BOUND('',#1314,.T.);
+#1102=FACE_OUTER_BOUND('',#1315,.T.);
+#1103=FACE_OUTER_BOUND('',#1316,.T.);
+#1104=FACE_OUTER_BOUND('',#1317,.T.);
+#1105=FACE_OUTER_BOUND('',#1318,.T.);
+#1106=FACE_OUTER_BOUND('',#1319,.T.);
+#1107=FACE_OUTER_BOUND('',#1320,.T.);
+#1108=FACE_OUTER_BOUND('',#1321,.T.);
+#1109=FACE_OUTER_BOUND('',#1322,.T.);
+#1110=FACE_OUTER_BOUND('',#1323,.T.);
+#1111=FACE_OUTER_BOUND('',#1324,.T.);
+#1112=FACE_OUTER_BOUND('',#1325,.T.);
+#1113=FACE_OUTER_BOUND('',#1326,.T.);
+#1114=FACE_OUTER_BOUND('',#1327,.T.);
+#1115=FACE_OUTER_BOUND('',#1328,.T.);
+#1116=FACE_OUTER_BOUND('',#1329,.T.);
+#1117=FACE_OUTER_BOUND('',#1330,.T.);
+#1118=FACE_OUTER_BOUND('',#1331,.T.);
+#1119=FACE_OUTER_BOUND('',#1332,.T.);
+#1120=FACE_OUTER_BOUND('',#1333,.T.);
+#1121=FACE_OUTER_BOUND('',#1334,.T.);
+#1122=FACE_OUTER_BOUND('',#1335,.T.);
+#1123=FACE_OUTER_BOUND('',#1336,.T.);
+#1124=FACE_OUTER_BOUND('',#1337,.T.);
+#1125=FACE_OUTER_BOUND('',#1338,.T.);
+#1126=FACE_OUTER_BOUND('',#1339,.T.);
+#1127=FACE_OUTER_BOUND('',#1340,.T.);
+#1128=FACE_OUTER_BOUND('',#1341,.T.);
+#1129=FACE_OUTER_BOUND('',#1342,.T.);
+#1130=FACE_OUTER_BOUND('',#1343,.T.);
+#1131=FACE_OUTER_BOUND('',#1344,.T.);
+#1132=FACE_OUTER_BOUND('',#1345,.T.);
+#1133=FACE_OUTER_BOUND('',#1346,.T.);
+#1134=FACE_OUTER_BOUND('',#1347,.T.);
+#1135=FACE_OUTER_BOUND('',#1348,.T.);
+#1136=FACE_OUTER_BOUND('',#1349,.T.);
+#1137=FACE_OUTER_BOUND('',#1350,.T.);
+#1138=FACE_OUTER_BOUND('',#1351,.T.);
+#1139=FACE_OUTER_BOUND('',#1352,.T.);
+#1140=FACE_OUTER_BOUND('',#1353,.T.);
+#1141=FACE_OUTER_BOUND('',#1354,.T.);
+#1142=FACE_OUTER_BOUND('',#1355,.T.);
+#1143=FACE_OUTER_BOUND('',#1356,.T.);
+#1144=FACE_OUTER_BOUND('',#1357,.T.);
+#1145=FACE_OUTER_BOUND('',#1358,.T.);
+#1146=FACE_OUTER_BOUND('',#1359,.T.);
+#1147=FACE_OUTER_BOUND('',#1360,.T.);
+#1148=FACE_OUTER_BOUND('',#1361,.T.);
+#1149=FACE_OUTER_BOUND('',#1362,.T.);
+#1150=FACE_OUTER_BOUND('',#1363,.T.);
+#1151=FACE_OUTER_BOUND('',#1388,.T.);
+#1152=FACE_OUTER_BOUND('',#1389,.T.);
+#1153=FACE_OUTER_BOUND('',#1390,.T.);
+#1154=FACE_OUTER_BOUND('',#1391,.T.);
+#1155=FACE_OUTER_BOUND('',#1392,.T.);
+#1156=FACE_OUTER_BOUND('',#1393,.T.);
+#1157=FACE_OUTER_BOUND('',#1394,.T.);
+#1158=FACE_OUTER_BOUND('',#1395,.T.);
+#1159=FACE_OUTER_BOUND('',#1396,.T.);
+#1160=FACE_OUTER_BOUND('',#1397,.T.);
+#1161=FACE_OUTER_BOUND('',#1398,.T.);
+#1162=FACE_OUTER_BOUND('',#1399,.T.);
+#1163=FACE_OUTER_BOUND('',#1400,.T.);
+#1164=FACE_OUTER_BOUND('',#1401,.T.);
+#1165=FACE_OUTER_BOUND('',#1402,.T.);
+#1166=EDGE_LOOP('',(#2407,#2408,#2409,#2410,#2411));
+#1167=EDGE_LOOP('',(#2412,#2413,#2414,#2415,#2416));
+#1168=EDGE_LOOP('',(#2417,#2418,#2419,#2420,#2421,#2422,#2423,#2424,#2425,
+#2426));
+#1169=EDGE_LOOP('',(#2427,#2428));
+#1170=EDGE_LOOP('',(#2429));
+#1171=EDGE_LOOP('',(#2430,#2431,#2432,#2433));
+#1172=EDGE_LOOP('',(#2434,#2435,#2436,#2437));
+#1173=EDGE_LOOP('',(#2438,#2439,#2440,#2441));
+#1174=EDGE_LOOP('',(#2442,#2443,#2444,#2445));
+#1175=EDGE_LOOP('',(#2446,#2447,#2448,#2449));
+#1176=EDGE_LOOP('',(#2450,#2451,#2452,#2453));
+#1177=EDGE_LOOP('',(#2454,#2455,#2456,#2457));
+#1178=EDGE_LOOP('',(#2458,#2459,#2460,#2461));
+#1179=EDGE_LOOP('',(#2462,#2463,#2464,#2465));
+#1180=EDGE_LOOP('',(#2466,#2467,#2468,#2469));
+#1181=EDGE_LOOP('',(#2470,#2471,#2472,#2473));
+#1182=EDGE_LOOP('',(#2474,#2475,#2476,#2477));
+#1183=EDGE_LOOP('',(#2478,#2479,#2480,#2481));
+#1184=EDGE_LOOP('',(#2482,#2483,#2484,#2485));
+#1185=EDGE_LOOP('',(#2486,#2487,#2488,#2489));
+#1186=EDGE_LOOP('',(#2490,#2491,#2492,#2493));
+#1187=EDGE_LOOP('',(#2494,#2495,#2496,#2497));
+#1188=EDGE_LOOP('',(#2498,#2499,#2500,#2501));
+#1189=EDGE_LOOP('',(#2502,#2503,#2504,#2505));
+#1190=EDGE_LOOP('',(#2506,#2507,#2508,#2509));
+#1191=EDGE_LOOP('',(#2510,#2511,#2512,#2513));
+#1192=EDGE_LOOP('',(#2514,#2515,#2516,#2517));
+#1193=EDGE_LOOP('',(#2518,#2519,#2520,#2521));
+#1194=EDGE_LOOP('',(#2522,#2523,#2524,#2525));
+#1195=EDGE_LOOP('',(#2526,#2527,#2528,#2529));
+#1196=EDGE_LOOP('',(#2530,#2531,#2532,#2533));
+#1197=EDGE_LOOP('',(#2534,#2535,#2536,#2537));
+#1198=EDGE_LOOP('',(#2538,#2539,#2540,#2541,#2542,#2543));
+#1199=EDGE_LOOP('',(#2544,#2545,#2546,#2547,#2548,#2549));
+#1200=EDGE_LOOP('',(#2550,#2551,#2552,#2553,#2554,#2555,#2556,#2557,#2558,
+#2559,#2560,#2561));
+#1201=EDGE_LOOP('',(#2562,#2563,#2564,#2565));
+#1202=EDGE_LOOP('',(#2566,#2567,#2568,#2569));
+#1203=EDGE_LOOP('',(#2570,#2571,#2572,#2573,#2574,#2575,#2576,#2577,#2578,
+#2579,#2580,#2581,#2582,#2583,#2584,#2585,#2586,#2587,#2588,#2589,#2590,
+#2591,#2592,#2593,#2594,#2595,#2596,#2597,#2598,#2599,#2600,#2601,#2602,
+#2603,#2604,#2605,#2606,#2607,#2608,#2609,#2610,#2611));
+#1204=EDGE_LOOP('',(#2612));
+#1205=EDGE_LOOP('',(#2613));
+#1206=EDGE_LOOP('',(#2614));
+#1207=EDGE_LOOP('',(#2615));
+#1208=EDGE_LOOP('',(#2616,#2617,#2618,#2619,#2620,#2621,#2622,#2623));
+#1209=EDGE_LOOP('',(#2624,#2625,#2626));
+#1210=EDGE_LOOP('',(#2627,#2628,#2629,#2630,#2631,#2632));
+#1211=EDGE_LOOP('',(#2633,#2634,#2635,#2636,#2637));
+#1212=EDGE_LOOP('',(#2638,#2639,#2640,#2641));
+#1213=EDGE_LOOP('',(#2642,#2643,#2644));
+#1214=EDGE_LOOP('',(#2645,#2646,#2647,#2648,#2649,#2650));
+#1215=EDGE_LOOP('',(#2651,#2652,#2653,#2654,#2655));
+#1216=EDGE_LOOP('',(#2656,#2657,#2658,#2659));
+#1217=EDGE_LOOP('',(#2660,#2661,#2662,#2663));
+#1218=EDGE_LOOP('',(#2664,#2665,#2666,#2667,#2668));
+#1219=EDGE_LOOP('',(#2669,#2670,#2671,#2672,#2673));
+#1220=EDGE_LOOP('',(#2674,#2675,#2676,#2677,#2678,#2679,#2680,#2681,#2682,
+#2683,#2684,#2685,#2686,#2687,#2688,#2689,#2690,#2691,#2692));
+#1221=EDGE_LOOP('',(#2693,#2694,#2695,#2696));
+#1222=EDGE_LOOP('',(#2697,#2698,#2699,#2700));
+#1223=EDGE_LOOP('',(#2701,#2702,#2703,#2704));
+#1224=EDGE_LOOP('',(#2705,#2706,#2707,#2708));
+#1225=EDGE_LOOP('',(#2709,#2710,#2711,#2712));
+#1226=EDGE_LOOP('',(#2713,#2714,#2715,#2716));
+#1227=EDGE_LOOP('',(#2717,#2718,#2719,#2720));
+#1228=EDGE_LOOP('',(#2721,#2722,#2723,#2724));
+#1229=EDGE_LOOP('',(#2725,#2726,#2727,#2728,#2729));
+#1230=EDGE_LOOP('',(#2730,#2731,#2732,#2733));
+#1231=EDGE_LOOP('',(#2734,#2735,#2736,#2737,#2738,#2739,#2740,#2741,#2742,
+#2743));
+#1232=EDGE_LOOP('',(#2744,#2745,#2746,#2747));
+#1233=EDGE_LOOP('',(#2748,#2749,#2750,#2751));
+#1234=EDGE_LOOP('',(#2752,#2753,#2754,#2755));
+#1235=EDGE_LOOP('',(#2756,#2757,#2758,#2759));
+#1236=EDGE_LOOP('',(#2760,#2761,#2762));
+#1237=EDGE_LOOP('',(#2763,#2764,#2765,#2766));
+#1238=EDGE_LOOP('',(#2767,#2768,#2769));
+#1239=EDGE_LOOP('',(#2770,#2771,#2772,#2773));
+#1240=EDGE_LOOP('',(#2774,#2775,#2776,#2777));
+#1241=EDGE_LOOP('',(#2778,#2779,#2780,#2781));
+#1242=EDGE_LOOP('',(#2782,#2783,#2784,#2785));
+#1243=EDGE_LOOP('',(#2786,#2787,#2788,#2789));
+#1244=EDGE_LOOP('',(#2790,#2791,#2792,#2793));
+#1245=EDGE_LOOP('',(#2794,#2795,#2796,#2797));
+#1246=EDGE_LOOP('',(#2798,#2799,#2800,#2801));
+#1247=EDGE_LOOP('',(#2802,#2803,#2804,#2805));
+#1248=EDGE_LOOP('',(#2806,#2807,#2808,#2809));
+#1249=EDGE_LOOP('',(#2810,#2811,#2812,#2813));
+#1250=EDGE_LOOP('',(#2814,#2815,#2816,#2817));
+#1251=EDGE_LOOP('',(#2818,#2819,#2820,#2821,#2822,#2823,#2824,#2825));
+#1252=EDGE_LOOP('',(#2826,#2827,#2828,#2829));
+#1253=EDGE_LOOP('',(#2830,#2831,#2832,#2833,#2834));
+#1254=EDGE_LOOP('',(#2835,#2836,#2837,#2838,#2839,#2840,#2841,#2842,#2843));
+#1255=EDGE_LOOP('',(#2844));
+#1256=EDGE_LOOP('',(#2845));
+#1257=EDGE_LOOP('',(#2846,#2847,#2848,#2849));
+#1258=EDGE_LOOP('',(#2850,#2851,#2852,#2853));
+#1259=EDGE_LOOP('',(#2854));
+#1260=EDGE_LOOP('',(#2855,#2856,#2857,#2858));
+#1261=EDGE_LOOP('',(#2859));
+#1262=EDGE_LOOP('',(#2860,#2861,#2862,#2863));
+#1263=EDGE_LOOP('',(#2864));
+#1264=EDGE_LOOP('',(#2865,#2866,#2867,#2868));
+#1265=EDGE_LOOP('',(#2869));
+#1266=EDGE_LOOP('',(#2870,#2871,#2872,#2873,#2874,#2875));
+#1267=EDGE_LOOP('',(#2876,#2877,#2878));
+#1268=EDGE_LOOP('',(#2879,#2880,#2881,#2882));
+#1269=EDGE_LOOP('',(#2883,#2884,#2885,#2886));
+#1270=EDGE_LOOP('',(#2887,#2888,#2889,#2890));
+#1271=EDGE_LOOP('',(#2891,#2892,#2893,#2894));
+#1272=EDGE_LOOP('',(#2895,#2896,#2897,#2898));
+#1273=EDGE_LOOP('',(#2899,#2900,#2901,#2902));
+#1274=EDGE_LOOP('',(#2903,#2904,#2905,#2906,#2907,#2908,#2909));
+#1275=EDGE_LOOP('',(#2910,#2911,#2912,#2913,#2914));
+#1276=EDGE_LOOP('',(#2915,#2916,#2917,#2918,#2919));
+#1277=EDGE_LOOP('',(#2920,#2921,#2922,#2923,#2924,#2925));
+#1278=EDGE_LOOP('',(#2926,#2927,#2928,#2929));
+#1279=EDGE_LOOP('',(#2930,#2931,#2932,#2933));
+#1280=EDGE_LOOP('',(#2934));
+#1281=EDGE_LOOP('',(#2935));
+#1282=EDGE_LOOP('',(#2936));
+#1283=EDGE_LOOP('',(#2937));
+#1284=EDGE_LOOP('',(#2938));
+#1285=EDGE_LOOP('',(#2939));
+#1286=EDGE_LOOP('',(#2940,#2941,#2942,#2943));
+#1287=EDGE_LOOP('',(#2944));
+#1288=EDGE_LOOP('',(#2945,#2946,#2947,#2948));
+#1289=EDGE_LOOP('',(#2949));
+#1290=EDGE_LOOP('',(#2950,#2951,#2952,#2953));
+#1291=EDGE_LOOP('',(#2954));
+#1292=EDGE_LOOP('',(#2955,#2956,#2957,#2958));
+#1293=EDGE_LOOP('',(#2959));
+#1294=EDGE_LOOP('',(#2960,#2961,#2962,#2963));
+#1295=EDGE_LOOP('',(#2964,#2965,#2966,#2967));
+#1296=EDGE_LOOP('',(#2968,#2969,#2970,#2971));
+#1297=EDGE_LOOP('',(#2972,#2973,#2974,#2975));
+#1298=EDGE_LOOP('',(#2976,#2977,#2978,#2979));
+#1299=EDGE_LOOP('',(#2980,#2981,#2982,#2983));
+#1300=EDGE_LOOP('',(#2984,#2985,#2986,#2987));
+#1301=EDGE_LOOP('',(#2988,#2989,#2990,#2991));
+#1302=EDGE_LOOP('',(#2992,#2993,#2994,#2995));
+#1303=EDGE_LOOP('',(#2996,#2997,#2998,#2999));
+#1304=EDGE_LOOP('',(#3000,#3001,#3002,#3003));
+#1305=EDGE_LOOP('',(#3004,#3005,#3006,#3007));
+#1306=EDGE_LOOP('',(#3008,#3009,#3010,#3011));
+#1307=EDGE_LOOP('',(#3012,#3013,#3014,#3015));
+#1308=EDGE_LOOP('',(#3016,#3017,#3018,#3019));
+#1309=EDGE_LOOP('',(#3020,#3021,#3022,#3023));
+#1310=EDGE_LOOP('',(#3024,#3025,#3026,#3027));
+#1311=EDGE_LOOP('',(#3028,#3029,#3030,#3031));
+#1312=EDGE_LOOP('',(#3032,#3033,#3034,#3035));
+#1313=EDGE_LOOP('',(#3036,#3037,#3038,#3039));
+#1314=EDGE_LOOP('',(#3040,#3041,#3042,#3043));
+#1315=EDGE_LOOP('',(#3044,#3045,#3046,#3047));
+#1316=EDGE_LOOP('',(#3048,#3049,#3050,#3051));
+#1317=EDGE_LOOP('',(#3052,#3053,#3054,#3055));
+#1318=EDGE_LOOP('',(#3056,#3057,#3058,#3059));
+#1319=EDGE_LOOP('',(#3060,#3061,#3062,#3063));
+#1320=EDGE_LOOP('',(#3064,#3065,#3066,#3067));
+#1321=EDGE_LOOP('',(#3068,#3069,#3070,#3071));
+#1322=EDGE_LOOP('',(#3072,#3073,#3074,#3075));
+#1323=EDGE_LOOP('',(#3076,#3077,#3078,#3079));
+#1324=EDGE_LOOP('',(#3080,#3081,#3082,#3083));
+#1325=EDGE_LOOP('',(#3084,#3085,#3086,#3087));
+#1326=EDGE_LOOP('',(#3088,#3089,#3090,#3091));
+#1327=EDGE_LOOP('',(#3092,#3093,#3094,#3095));
+#1328=EDGE_LOOP('',(#3096,#3097,#3098,#3099));
+#1329=EDGE_LOOP('',(#3100,#3101,#3102,#3103));
+#1330=EDGE_LOOP('',(#3104,#3105,#3106,#3107));
+#1331=EDGE_LOOP('',(#3108,#3109,#3110,#3111));
+#1332=EDGE_LOOP('',(#3112,#3113,#3114,#3115));
+#1333=EDGE_LOOP('',(#3116,#3117,#3118,#3119));
+#1334=EDGE_LOOP('',(#3120,#3121,#3122,#3123));
+#1335=EDGE_LOOP('',(#3124,#3125,#3126,#3127));
+#1336=EDGE_LOOP('',(#3128,#3129,#3130,#3131));
+#1337=EDGE_LOOP('',(#3132,#3133,#3134,#3135));
+#1338=EDGE_LOOP('',(#3136,#3137,#3138,#3139));
+#1339=EDGE_LOOP('',(#3140,#3141,#3142,#3143));
+#1340=EDGE_LOOP('',(#3144));
+#1341=EDGE_LOOP('',(#3145,#3146,#3147,#3148));
+#1342=EDGE_LOOP('',(#3149));
+#1343=EDGE_LOOP('',(#3150,#3151,#3152,#3153));
+#1344=EDGE_LOOP('',(#3154));
+#1345=EDGE_LOOP('',(#3155,#3156,#3157,#3158));
+#1346=EDGE_LOOP('',(#3159));
+#1347=EDGE_LOOP('',(#3160,#3161,#3162,#3163));
+#1348=EDGE_LOOP('',(#3164));
+#1349=EDGE_LOOP('',(#3165,#3166,#3167,#3168));
+#1350=EDGE_LOOP('',(#3169,#3170,#3171,#3172));
+#1351=EDGE_LOOP('',(#3173,#3174,#3175,#3176));
+#1352=EDGE_LOOP('',(#3177,#3178));
+#1353=EDGE_LOOP('',(#3179,#3180,#3181,#3182));
+#1354=EDGE_LOOP('',(#3183,#3184,#3185,#3186));
+#1355=EDGE_LOOP('',(#3187,#3188,#3189,#3190));
+#1356=EDGE_LOOP('',(#3191,#3192,#3193,#3194));
+#1357=EDGE_LOOP('',(#3195,#3196,#3197,#3198));
+#1358=EDGE_LOOP('',(#3199,#3200,#3201,#3202));
+#1359=EDGE_LOOP('',(#3203,#3204,#3205,#3206));
+#1360=EDGE_LOOP('',(#3207,#3208,#3209,#3210));
+#1361=EDGE_LOOP('',(#3211,#3212,#3213,#3214));
+#1362=EDGE_LOOP('',(#3215,#3216,#3217,#3218));
+#1363=EDGE_LOOP('',(#3219,#3220,#3221,#3222,#3223,#3224,#3225,#3226,#3227,
+#3228,#3229,#3230,#3231,#3232,#3233,#3234));
+#1364=EDGE_LOOP('',(#3235,#3236));
+#1365=EDGE_LOOP('',(#3237,#3238,#3239,#3240));
+#1366=EDGE_LOOP('',(#3241,#3242,#3243,#3244));
+#1367=EDGE_LOOP('',(#3245,#3246,#3247,#3248));
+#1368=EDGE_LOOP('',(#3249,#3250,#3251,#3252));
+#1369=EDGE_LOOP('',(#3253,#3254,#3255,#3256));
+#1370=EDGE_LOOP('',(#3257));
+#1371=EDGE_LOOP('',(#3258));
+#1372=EDGE_LOOP('',(#3259));
+#1373=EDGE_LOOP('',(#3260,#3261,#3262,#3263));
+#1374=EDGE_LOOP('',(#3264,#3265,#3266,#3267));
+#1375=EDGE_LOOP('',(#3268,#3269,#3270,#3271));
+#1376=EDGE_LOOP('',(#3272,#3273,#3274,#3275));
+#1377=EDGE_LOOP('',(#3276,#3277,#3278,#3279));
+#1378=EDGE_LOOP('',(#3280,#3281,#3282,#3283));
+#1379=EDGE_LOOP('',(#3284,#3285,#3286,#3287));
+#1380=EDGE_LOOP('',(#3288,#3289,#3290,#3291));
+#1381=EDGE_LOOP('',(#3292,#3293,#3294,#3295));
+#1382=EDGE_LOOP('',(#3296,#3297,#3298,#3299));
+#1383=EDGE_LOOP('',(#3300));
+#1384=EDGE_LOOP('',(#3301));
+#1385=EDGE_LOOP('',(#3302));
+#1386=EDGE_LOOP('',(#3303));
+#1387=EDGE_LOOP('',(#3304));
+#1388=EDGE_LOOP('',(#3305,#3306,#3307,#3308));
+#1389=EDGE_LOOP('',(#3309,#3310,#3311,#3312));
+#1390=EDGE_LOOP('',(#3313,#3314,#3315,#3316,#3317,#3318,#3319,#3320));
+#1391=EDGE_LOOP('',(#3321,#3322,#3323,#3324));
+#1392=EDGE_LOOP('',(#3325,#3326,#3327,#3328));
+#1393=EDGE_LOOP('',(#3329,#3330,#3331,#3332));
+#1394=EDGE_LOOP('',(#3333,#3334,#3335,#3336,#3337,#3338,#3339,#3340));
+#1395=EDGE_LOOP('',(#3341,#3342,#3343,#3344));
+#1396=EDGE_LOOP('',(#3345,#3346,#3347,#3348));
+#1397=EDGE_LOOP('',(#3349,#3350,#3351,#3352,#3353,#3354));
+#1398=EDGE_LOOP('',(#3355,#3356,#3357,#3358));
+#1399=EDGE_LOOP('',(#3359,#3360,#3361,#3362));
+#1400=EDGE_LOOP('',(#3363,#3364,#3365,#3366));
+#1401=EDGE_LOOP('',(#3367,#3368,#3369,#3370));
+#1402=EDGE_LOOP('',(#3371,#3372,#3373,#3374));
+#1403=CIRCLE('',#3605,2.99999999999999);
+#1404=CIRCLE('',#3606,3.);
+#1405=CIRCLE('',#3609,3.75);
+#1406=CIRCLE('',#3610,1.5);
+#1407=CIRCLE('',#3612,3.75);
+#1408=CIRCLE('',#3613,3.375);
+#1409=CIRCLE('',#3640,2.75);
+#1410=CIRCLE('',#3641,2.75);
+#1411=CIRCLE('',#3642,2.75);
+#1412=CIRCLE('',#3644,2.75);
+#1413=CIRCLE('',#3645,2.75);
+#1414=CIRCLE('',#3646,2.75);
+#1415=CIRCLE('',#3649,8.5);
+#1416=CIRCLE('',#3650,8.5);
+#1417=CIRCLE('',#3652,8.5);
+#1418=CIRCLE('',#3653,8.5);
+#1419=CIRCLE('',#3655,172.);
+#1420=CIRCLE('',#3656,5.);
+#1421=CIRCLE('',#3657,7.);
+#1422=CIRCLE('',#3658,5.);
+#1423=CIRCLE('',#3659,7.);
+#1424=CIRCLE('',#3660,178.000000000002);
+#1425=CIRCLE('',#3661,7.);
+#1426=CIRCLE('',#3662,5.);
+#1427=CIRCLE('',#3663,7.);
+#1428=CIRCLE('',#3664,5.);
+#1429=CIRCLE('',#3665,172.);
+#1430=CIRCLE('',#3666,2.);
+#1431=CIRCLE('',#3667,2.);
+#1432=CIRCLE('',#3668,175.);
+#1433=CIRCLE('',#3669,10.);
+#1434=CIRCLE('',#3670,5.);
+#1435=CIRCLE('',#3671,10.);
+#1436=CIRCLE('',#3672,10.);
+#1437=CIRCLE('',#3673,175.000000000002);
+#1438=CIRCLE('',#3674,10.);
+#1439=CIRCLE('',#3675,5.);
+#1440=CIRCLE('',#3676,10.);
+#1441=CIRCLE('',#3677,10.);
+#1442=CIRCLE('',#3678,5.);
+#1443=CIRCLE('',#3679,10.);
+#1444=CIRCLE('',#3680,175.);
+#1445=CIRCLE('',#3681,2.);
+#1446=CIRCLE('',#3682,2.);
+#1447=CIRCLE('',#3683,2.75);
+#1448=CIRCLE('',#3684,2.75);
+#1449=CIRCLE('',#3685,2.75);
+#1450=CIRCLE('',#3686,2.75);
+#1451=CIRCLE('',#3689,2.);
+#1452=CIRCLE('',#3690,1.99999999999999);
+#1453=CIRCLE('',#3691,1.99999999999999);
+#1454=CIRCLE('',#3693,2.);
+#1455=CIRCLE('',#3695,2.);
+#1456=CIRCLE('',#3697,1.99999999999999);
+#1457=CIRCLE('',#3698,2.);
+#1458=CIRCLE('',#3699,1.99999999999999);
+#1459=CIRCLE('',#3701,1.99999999999999);
+#1460=CIRCLE('',#3704,2.);
+#1461=CIRCLE('',#3706,4.);
+#1462=CIRCLE('',#3708,2.);
+#1463=CIRCLE('',#3709,1.99999999999999);
+#1464=CIRCLE('',#3711,8.);
+#1465=CIRCLE('',#3712,177.000000000002);
+#1466=CIRCLE('',#3713,8.);
+#1467=CIRCLE('',#3714,8.);
+#1468=CIRCLE('',#3715,173.);
+#1469=CIRCLE('',#3716,3.99999999999997);
+#1470=CIRCLE('',#3717,3.99999999999999);
+#1471=CIRCLE('',#3718,173.);
+#1472=CIRCLE('',#3719,8.);
+#1473=CIRCLE('',#3722,2.);
+#1474=CIRCLE('',#3724,2.);
+#1475=CIRCLE('',#3725,2.00000000000001);
+#1476=CIRCLE('',#3727,10.);
+#1477=CIRCLE('',#3728,2.);
+#1478=CIRCLE('',#3730,10.);
+#1479=CIRCLE('',#3731,10.);
+#1480=CIRCLE('',#3733,2.);
+#1481=CIRCLE('',#3734,2.);
+#1482=CIRCLE('',#3735,1.99999999999999);
+#1483=CIRCLE('',#3737,2.);
+#1484=CIRCLE('',#3739,2.);
+#1485=CIRCLE('',#3740,10.);
+#1486=CIRCLE('',#3742,175.);
+#1487=CIRCLE('',#3744,1.99999999999998);
+#1488=CIRCLE('',#3745,2.);
+#1489=CIRCLE('',#3746,1.99999999999999);
+#1490=CIRCLE('',#3749,1.99999999999999);
+#1491=CIRCLE('',#3750,2.);
+#1492=CIRCLE('',#3751,1.99999999999999);
+#1493=CIRCLE('',#3754,2.);
+#1494=CIRCLE('',#3755,2.);
+#1495=CIRCLE('',#3756,1.99999999999997);
+#1496=CIRCLE('',#3759,2.);
+#1497=CIRCLE('',#3760,175.);
+#1498=CIRCLE('',#3762,2.);
+#1499=CIRCLE('',#3763,10.);
+#1500=CIRCLE('',#3765,2.);
+#1501=CIRCLE('',#3767,2.);
+#1502=CIRCLE('',#3768,10.);
+#1503=CIRCLE('',#3770,175.000000000002);
+#1504=CIRCLE('',#3776,10.);
+#1505=CIRCLE('',#3782,1.5);
+#1506=CIRCLE('',#3783,1.5);
+#1507=CIRCLE('',#3786,1.5);
+#1508=CIRCLE('',#3789,1.5);
+#1509=CIRCLE('',#3790,1.5);
+#1510=CIRCLE('',#3793,1.5);
+#1511=CIRCLE('',#3794,1.5);
+#1512=CIRCLE('',#3796,2.99999999999999);
+#1513=CIRCLE('',#3798,3.);
+#1514=CIRCLE('',#3800,3.75);
+#1515=CIRCLE('',#3802,3.);
+#1516=CIRCLE('',#3803,3.);
+#1517=CIRCLE('',#3804,3.375);
+#1518=CIRCLE('',#3805,3.75000000000002);
+#1519=CIRCLE('',#3806,3.);
+#1520=CIRCLE('',#3808,3.);
+#1521=CIRCLE('',#3810,3.75);
+#1522=CIRCLE('',#3811,3.);
+#1523=CIRCLE('',#3813,3.);
+#1524=CIRCLE('',#3815,3.75);
+#1525=CIRCLE('',#3817,3.);
+#1526=CIRCLE('',#3819,3.);
+#1527=CIRCLE('',#3824,2.75);
+#1528=CIRCLE('',#3827,2.75);
+#1529=CIRCLE('',#3830,2.75);
+#1530=CIRCLE('',#3833,2.75);
+#1531=CIRCLE('',#3881,1.45);
+#1532=CIRCLE('',#3882,1.45);
+#1533=CIRCLE('',#3885,1.45);
+#1534=CIRCLE('',#3886,1.45);
+#1535=CIRCLE('',#3889,1.45);
+#1536=CIRCLE('',#3890,1.45);
+#1537=CIRCLE('',#3893,1.45);
+#1538=CIRCLE('',#3894,1.45);
+#1539=CIRCLE('',#3897,1.45);
+#1540=CIRCLE('',#3898,1.45);
+#1541=CIRCLE('',#3901,5.);
+#1542=CIRCLE('',#3904,5.);
+#1543=CIRCLE('',#3906,5.);
+#1544=CIRCLE('',#3909,5.);
+#1545=CIRCLE('',#3911,10.);
+#1546=CIRCLE('',#3913,5.);
+#1547=CIRCLE('',#3916,7.);
+#1548=CIRCLE('',#3918,7.);
+#1549=CIRCLE('',#3921,7.);
+#1550=CIRCLE('',#3923,7.);
+#1551=CIRCLE('',#3925,172.);
+#1552=CIRCLE('',#3926,172.);
+#1553=CIRCLE('',#3927,178.000000000002);
+#1554=CIRCLE('',#3943,175.);
+#1555=CIRCLE('',#3944,175.000000000002);
+#1556=CIRCLE('',#3945,5.);
+#1557=CIRCLE('',#3946,10.);
+#1558=CIRCLE('',#3947,5.);
+#1559=CIRCLE('',#3948,10.);
+#1560=CIRCLE('',#3949,5.);
+#1561=CIRCLE('',#3950,5.);
+#1562=CIRCLE('',#3951,174.999999999999);
+#1563=CIRCLE('',#3952,175.);
+#1564=CIRCLE('',#3953,1.45);
+#1565=CIRCLE('',#3954,1.45);
+#1566=CIRCLE('',#3955,1.45);
+#1567=CIRCLE('',#3956,1.45);
+#1568=CIRCLE('',#3957,1.45);
+#1569=CIRCLE('',#3958,2.75);
+#1570=CIRCLE('',#3959,2.75);
+#1571=CIRCLE('',#3960,2.75);
+#1572=CIRCLE('',#3961,2.75);
+#1573=CIRCLE('',#3962,3.);
+#1574=CIRCLE('',#3963,3.);
+#1575=CIRCLE('',#3964,3.);
+#1576=CIRCLE('',#3965,3.);
+#1577=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5009,#5010,#5011,#5012),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(-1.,-0.314417631318541),.UNSPECIFIED.);
+#1578=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5014,#5015,#5016,#5017),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(-5.55111512312578E-16,0.0253965068716328),
+ .UNSPECIFIED.);
+#1579=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5019,#5020,#5021,#5022),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(0.0253965068716328,0.0524068809145321),
+ .UNSPECIFIED.);
+#1580=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5025,#5026,#5027,#5028),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(-2.26336806474523,-1.67097580212346),
+ .UNSPECIFIED.);
+#1581=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5091,#5092,#5093,#5094),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(-1.,-0.30196909293401),.UNSPECIFIED.);
+#1582=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5095,#5096,#5097,#5098,#5099,#5100,
+#5101,#5102,#5103,#5104,#5105,#5106,#5107,#5108,#5109),.UNSPECIFIED.,.F.,
+ .F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),(-3.44169137633799E-15,0.0673485414173676,
+0.134697082834739,0.168371353543424,0.20204562425211,0.2244951380579,0.269394165669481,
+0.280618922572376,0.291843679475271,0.336742707086852,0.370416977795537,
+0.404091248504223,0.471439789921594),.UNSPECIFIED.);
+#1583=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5113,#5114,#5115,#5116),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(-3.14169216607747,-3.14165705771262),
+ .UNSPECIFIED.);
+#1584=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5117,#5118,#5119,#5120,#5121,#5122,
+#5123,#5124,#5125,#5126,#5127,#5128,#5129,#5130,#5131,#5132,#5133,#5134,
+#5135,#5136,#5137,#5138,#5139,#5140,#5141,#5142,#5143,#5144,#5145,#5146,
+#5147,#5148,#5149,#5150,#5151,#5152,#5153,#5154,#5155,#5156,#5157,#5158,
+#5159,#5160,#5161,#5162,#5163,#5164,#5165,#5166,#5167,#5168,#5169,#5170,
+#5171,#5172,#5173,#5174,#5175,#5176,#5177,#5178,#5179,#5180,#5181,#5182,
+#5183,#5184,#5185,#5186,#5187,#5188,#5189,#5190,#5191,#5192,#5193,#5194,
+#5195,#5196,#5197,#5198,#5199,#5200,#5201,#5202,#5203,#5204,#5205,#5206,
+#5207,#5208,#5209,#5210,#5211,#5212,#5213,#5214,#5215,#5216,#5217,#5218,
+#5219,#5220,#5221,#5222,#5223,#5224,#5225,#5226,#5227,#5228,#5229,#5230,
+#5231,#5232,#5233,#5234,#5235,#5236,#5237,#5238,#5239,#5240,#5241,#5242,
+#5243,#5244,#5245,#5246,#5247,#5248,#5249,#5250,#5251,#5252,#5253,#5254,
+#5255,#5256,#5257,#5258,#5259,#5260,#5261,#5262,#5263,#5264,#5265,#5266,
+#5267,#5268,#5269,#5270,#5271,#5272,#5273,#5274,#5275,#5276,#5277,#5278,
+#5279,#5280,#5281,#5282,#5283,#5284,#5285,#5286,#5287,#5288,#5289,#5290,
+#5291,#5292,#5293,#5294,#5295,#5296,#5297,#5298,#5299,#5300,#5301,#5302,
+#5303,#5304,#5305,#5306,#5307,#5308,#5309,#5310,#5311,#5312,#5313,#5314,
+#5315,#5316,#5317,#5318,#5319,#5320,#5321,#5322,#5323,#5324,#5325,#5326,
+#5327,#5328,#5329,#5330,#5331,#5332,#5333,#5334,#5335,#5336,#5337,#5338,
+#5339),.UNSPECIFIED.,.F.,.F.,(4,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,
+3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,
+3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,4),(-3.14155287977,-3.04967168196976,
+-2.95462207929751,-2.85837425208694,-2.76183892874286,-2.74952603556418,
+-2.61509199234741,-2.47270893130196,-2.35703528786106,-2.30811082484854,
+-2.19109185257026,-2.07739261606809,-1.96369337956592,-1.86202170887921,
+-1.76230184274369,-1.66564457374369,-1.5689873047437,-1.47186683571153,
+-1.44080666954609,-1.34354576329329,-1.2494535216053,-1.17287664673813,
+-1.07249824520885,-0.981090163805031,-0.878678149019683,-0.776266134234335,
+-0.660352601276283,-0.547574646369297,-0.498913383843013,-0.392297679736514,
+-0.381076459747496,-0.249215206133694,-0.167154182078184,-0.0351266341330425,
+0.0106540009015466,0.113705493954558,0.215667627332177,0.314046503245495,
+0.398222982302229,0.48369876120119,0.499189343265606,0.588717680372713,
+0.662698265905798,0.746556114159891,0.782824979288739,0.823259626925372,
+0.909127067795516,0.993797410779438,1.08026340059269,1.16672939040595,1.25860967787629,
+1.35034290882608,1.44207613977587,1.53449195333014,1.55061001652922,1.65723100051611,
+1.7621399885881,1.86378313316062,1.88267565159337,1.93500507452762,2.04276930339139,
+2.14839899797245,2.24992442869675,2.30963211095331,2.3209358300892,2.42053874495104,
+2.52072794200054,2.61999921264015,2.7086456547056,2.81130337305948,2.91256892613207,
+2.92532990479517,3.01088772029537,3.09515428329634,3.14149314110212),
+ .UNSPECIFIED.);
+#1585=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5345,#5346,#5347,#5348,#5349,#5350,
+#5351,#5352),.UNSPECIFIED.,.F.,.F.,(4,2,2,4),(0.233364582493973,0.252070975881335,
+0.31923832763996,0.382605388252589),.UNSPECIFIED.);
+#1586=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5354,#5355,#5356,#5357,#5358,#5359,
+#5360,#5361),.UNSPECIFIED.,.F.,.F.,(4,2,2,4),(0.959001007727989,1.00383446356453,
+1.05580653560105,1.11139258298367),.UNSPECIFIED.);
+#1587=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5369,#5370,#5371,#5372,#5373,#5374,
+#5375,#5376),.UNSPECIFIED.,.F.,.F.,(4,2,2,4),(0.806609432472305,0.86219547985493,
+0.914167551891449,0.959001007727989),.UNSPECIFIED.);
+#1588=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5378,#5379,#5380,#5381,#5382,#5383,
+#5384,#5385),.UNSPECIFIED.,.F.,.F.,(4,2,2,4),(1.14781616475777,1.2111832253704,
+1.27835057712902,1.29705697051638),.UNSPECIFIED.);
+#1589=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5556,#5557,#5558,#5559,#5560,#5561,
+#5562,#5563,#5564,#5565),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,4),(1.31022345166491,
+1.32186868769577,1.41878032054159,1.51569195338741,1.5273371894183),
+ .UNSPECIFIED.);
+#1590=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5575,#5576,#5577,#5578,#5579,#5580,
+#5581,#5582,#5583,#5584),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,4),(1.31405348269246,
+1.3334096628534,1.43140994043558,1.52941021801777,1.5487663981787),
+ .UNSPECIFIED.);
+#1591=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5590,#5591,#5592,#5593,#5594,#5595,
+#5596,#5597),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),(-0.190826843895202,-0.166238944782744,
+-0.0831194723946981,-0.041559736200675,-0.0207798681036635,-6.65191408180362E-12),
+ .UNSPECIFIED.);
+#1592=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5601,#5602,#5603,#5604,#5605,#5606,
+#5607,#5608,#5609),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,4),(0.,0.0207747927006334,
+0.0415495854012669,0.0830991708025337,0.124648756203801,0.186973134305701,
+0.209426592321188),.UNSPECIFIED.);
+#1593=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5875,#5876,#5877,#5878,#5879,#5880,
+#5881,#5882,#5883,#5884,#5885,#5886,#5887,#5888,#5889,#5890,#5891,#5892,
+#5893,#5894),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,2,2,2,2,4),(0.0615659078800484,
+0.143184408837518,0.237480109236212,0.251010515022639,0.260606769977037,
+0.268883451272729,0.278562029671269,0.289848516430759,0.298654407096017,
+0.307477109589776),.UNSPECIFIED.);
+#1594=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5895,#5896,#5897,#5898,#5899,#5900,
+#5901,#5902,#5903,#5904,#5905,#5906,#5907,#5908,#5909,#5910,#5911,#5912,
+#5913,#5914,#5915,#5916,#5917,#5918,#5919,#5920,#5921),.UNSPECIFIED.,.F.,
+ .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.581694195617736,
+-0.581044983345841,-0.580395771073946,-0.579097346530157,-0.576500497442578,
+-0.573903648354999,-0.571306799267419,-0.560919402917103,-0.550532006566786,
+-0.540144610216469,-0.519369817515836,-0.498595024815202,-0.415495854012669,
+-0.360096406810979,-0.332396683210135,-0.322009286859818,-0.311621890509501,
+-0.290847097808868,-0.249297512407601,-0.186973134305701,-0.124648756203801,
+-0.0830991708025337,-0.0415495854012669,-0.0207747927006334,0.),
+ .UNSPECIFIED.);
+#1595=B_SPLINE_CURVE_WITH_KNOTS('',3,(#5922,#5923,#5924,#5925,#5926,#5927,
+#5928,#5929,#5930,#5931,#5932,#5933),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,4),
+(0.,0.0176858131613143,0.0446146758597362,0.0538008033290377,0.0575683015841299,
+0.0605231869720768),.UNSPECIFIED.);
+#1596=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6046,#6047,#6048,#6049,#6050,#6051,
+#6052,#6053,#6054,#6055,#6056,#6057,#6058,#6059,#6060,#6061,#6062,#6063,
+#6064,#6065,#6066,#6067,#6068,#6069,#6070,#6071,#6072,#6073,#6074,#6075,
+#6076,#6077,#6078,#6079,#6080,#6081,#6082),.UNSPECIFIED.,.F.,.F.,(4,3,3,
+3,3,3,3,3,3,3,3,3,4),(2.42617610217641E-5,0.00568138000038085,0.0133671175029703,
+0.0151562399907155,0.0240088421549811,0.032777487189885,0.0357589114266079,
+0.0444482469170436,0.0529887264644707,0.0552418767457102,0.0628228469152085,
+0.0700174201205289,0.0704038170847068),.UNSPECIFIED.);
+#1597=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6084,#6085,#6086,#6087,#6088,#6089,
+#6090,#6091,#6092,#6093,#6094,#6095,#6096,#6097,#6098,#6099,#6100,#6101,
+#6102),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(6.65191408180362E-12,
+0.0207798681036635,0.041559736200675,0.0831194723946981,0.166238944782744,
+0.332477889558837,0.37403762575286,0.457157098140906,0.498716834334929,
+0.519496702431941,0.529886636480446,0.540276570528952,0.550666504577458,
+0.561056438625964,0.57144637267447,0.576641339698722,0.581836306722975),
+ .UNSPECIFIED.);
+#1598=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6103,#6104,#6105,#6106,#6107,#6108,
+#6109,#6110,#6111,#6112,#6113,#6114,#6115,#6116,#6117,#6118,#6119,#6120),
+ .UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,2,2,2,4),(0.,0.000205405907166171,0.0178844497631975,
+0.0649734753510144,0.0793739703803107,0.0953557456301701,0.139108734957976,
+0.224936312764897,0.303107994565216),.UNSPECIFIED.);
+#1599=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6137,#6138,#6139,#6140),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(1.36626140532133,1.39911657146817),
+ .UNSPECIFIED.);
+#1600=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6147,#6148,#6149,#6150,#6151,#6152),
+ .UNSPECIFIED.,.F.,.F.,(4,2,4),(-0.00112142612860145,0.,0.0342603512793566),
+ .UNSPECIFIED.);
+#1601=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6264,#6265,#6266,#6267),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(-2.55265464418811,-2.54983890347792),
+ .UNSPECIFIED.);
+#1602=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6268,#6269,#6270,#6271,#6272,#6273),
+ .UNSPECIFIED.,.F.,.F.,(4,1,1,4),(2.54983890347792,2.73023275458932,2.91062660570071,
+3.18121738236781),.UNSPECIFIED.);
+#1603=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6436,#6437,#6438,#6439),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(-3.14165705771262,-3.14155287977001),
+ .UNSPECIFIED.);
+#1604=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6440,#6441,#6442,#6443,#6444,#6445,
+#6446,#6447,#6448,#6449),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,4),(-3.14149314110212,
+-2.24389524007646,-1.34629733905081,-0.448699438025151,0.448898463000504,
+1.34649636402616,2.24409426505181,3.14155287976858),.UNSPECIFIED.);
+#1605=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6566,#6567,#6568,#6569,#6570,#6571,
+#6572,#6573,#6574,#6575,#6576),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,4),
+(-3.80778963256358,-2.91019173153792,-2.01259383051227,-1.11499592948661,
+-0.217398028460956,0.680199872564699,0.904599347821113,1.57779777359035,
+2.22638910555705),.UNSPECIFIED.);
+#1606=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6577,#6578,#6579,#6580),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(2.22638910555705,2.47539567461601),
+ .UNSPECIFIED.);
+#1607=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6581,#6582,#6583,#6584),
+ .UNSPECIFIED.,.F.,.F.,(4,4),(-2.47539567461601,-2.26336806474523),
+ .UNSPECIFIED.);
+#1608=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6585,#6586,#6587,#6588,#6589,#6590,
+#6591,#6592,#6593,#6594,#6595,#6596,#6597,#6598,#6599,#6600,#6601,#6602,
+#6603,#6604,#6605,#6606,#6607,#6608,#6609),.UNSPECIFIED.,.F.,.F.,(4,3,3,
+3,3,3,3,3,4),(-1.67097580212346,-1.57779777359197,-0.904599347822526,-0.680199872566046,
+0.217398028459878,1.1149959294858,2.01259383051172,2.91019173153765,3.80778963256358),
+ .UNSPECIFIED.);
+#1609=B_SPLINE_CURVE_WITH_KNOTS('',3,(#6690,#6691,#6692,#6693,#6694,#6695,
+#6696,#6697,#6698,#6699,#6700,#6701,#6702,#6703,#6704,#6705,#6706,#6707,
+#6708,#6709,#6710,#6711,#6712,#6713,#6714,#6715,#6716,#6717,#6718,#6719,
+#6720,#6721,#6722,#6723,#6724,#6725,#6726,#6727,#6728,#6729,#6730,#6731,
+#6732,#6733,#6734,#6735,#6736,#6737,#6738,#6739,#6740,#6741,#6742,#6743,
+#6744,#6745,#6746,#6747,#6748,#6749,#6750,#6751,#6752,#6753,#6754,#6755,
+#6756,#6757,#6758,#6759,#6760,#6761,#6762,#6763,#6764,#6765,#6766,#6767,
+#6768,#6769,#6770,#6771,#6772,#6773,#6774,#6775,#6776,#6777,#6778,#6779,
+#6780,#6781,#6782,#6783,#6784,#6785,#6786,#6787,#6788,#6789,#6790,#6791,
+#6792,#6793,#6794,#6795,#6796,#6797,#6798,#6799,#6800,#6801,#6802,#6803,
+#6804,#6805,#6806,#6807,#6808,#6809,#6810,#6811,#6812,#6813,#6814,#6815,
+#6816,#6817,#6818,#6819,#6820,#6821,#6822,#6823,#6824,#6825,#6826,#6827,
+#6828,#6829,#6830,#6831,#6832,#6833,#6834,#6835,#6836,#6837,#6838,#6839,
+#6840,#6841,#6842,#6843,#6844,#6845,#6846,#6847,#6848,#6849,#6850,#6851,
+#6852,#6853,#6854,#6855,#6856,#6857,#6858,#6859,#6860,#6861,#6862,#6863,
+#6864,#6865,#6866,#6867,#6868,#6869,#6870,#6871,#6872,#6873,#6874,#6875,
+#6876,#6877,#6878,#6879,#6880,#6881,#6882,#6883,#6884,#6885,#6886,#6887,
+#6888,#6889,#6890,#6891,#6892,#6893,#6894,#6895,#6896,#6897,#6898,#6899,
+#6900,#6901,#6902,#6903,#6904,#6905,#6906,#6907,#6908,#6909,#6910,#6911,
+#6912,#6913,#6914,#6915,#6916,#6917,#6918,#6919,#6920,#6921,#6922,#6923,
+#6924,#6925,#6926,#6927,#6928,#6929,#6930,#6931,#6932,#6933,#6934,#6935,
+#6936,#6937,#6938,#6939,#6940,#6941,#6942,#6943,#6944,#6945,#6946,#6947,
+#6948,#6949,#6950,#6951),.UNSPECIFIED.,.F.,.F.,(4,3,3,3,3,3,3,3,3,3,3,3,
+3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,
+3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,
+3,3,3,4),(0.0524068809044223,0.0587367609838986,0.062291742377495,0.0641869941068415,
+0.0653289817838413,0.066080462299907,0.0724111305455344,0.0787889638163867,
+0.0851648785674523,0.091489134942999,0.0945050509853043,0.0952484124142755,
+0.0959834004818978,0.101672025731227,0.107306421457475,0.112832356869858,
+0.115616463281442,0.121229981412938,0.124492840686183,0.130732234314975,
+0.137033224135376,0.143335386646427,0.147206986467326,0.15286941965703,
+0.159753870257297,0.163008933162477,0.169930478990309,0.170889486471166,
+0.177467621648171,0.178781564646512,0.180978101768046,0.186534368389224,
+0.192253257073574,0.198048124233723,0.203921560703087,0.209269522865989,
+0.215941788024454,0.222717256240611,0.229485938722928,0.236161271870022,
+0.238186710225013,0.241956326015396,0.247736191338273,0.253666123027757,
+0.259672017088691,0.265758868283973,0.268178363240717,0.276032354944789,
+0.283769695175079,0.291682012616043,0.299594330057006,0.305238014016364,
+0.311680454884007,0.318210804018585,0.324879408725958,0.32624288848809,
+0.332272659428993,0.339979929697362,0.347303450642765,0.354741956829462,
+0.357813223932483,0.363081566062008,0.364152782371153,0.368350766016515,
+0.373937099524972,0.379497660751865,0.384935035850364,0.387209637858404,
+0.392013347186149,0.397741137404448,0.399899174861654,0.40575637250408,
+0.407125489795466,0.413150630437361,0.419292480251086,0.425572078702728,
+0.431025670572687,0.431489525447302,0.437623164954195,0.443835406229936,
+0.450099445275246,0.456451696579883,0.459593287824004,0.463087519538586,
+0.472283571411335,0.481506966146677,0.490571102176175,0.494679413004867),
+ .UNSPECIFIED.);
+#1610=VERTEX_POINT('',#5007);
+#1611=VERTEX_POINT('',#5008);
+#1612=VERTEX_POINT('',#5013);
+#1613=VERTEX_POINT('',#5018);
+#1614=VERTEX_POINT('',#5023);
+#1615=VERTEX_POINT('',#5089);
+#1616=VERTEX_POINT('',#5090);
+#1617=VERTEX_POINT('',#5110);
+#1618=VERTEX_POINT('',#5112);
+#1619=VERTEX_POINT('',#5341);
+#1620=VERTEX_POINT('',#5342);
+#1621=VERTEX_POINT('',#5344);
+#1622=VERTEX_POINT('',#5353);
+#1623=VERTEX_POINT('',#5362);
+#1624=VERTEX_POINT('',#5364);
+#1625=VERTEX_POINT('',#5366);
+#1626=VERTEX_POINT('',#5368);
+#1627=VERTEX_POINT('',#5377);
+#1628=VERTEX_POINT('',#5386);
+#1629=VERTEX_POINT('',#5391);
+#1630=VERTEX_POINT('',#5424);
+#1631=VERTEX_POINT('',#5425);
+#1632=VERTEX_POINT('',#5427);
+#1633=VERTEX_POINT('',#5429);
+#1634=VERTEX_POINT('',#5433);
+#1635=VERTEX_POINT('',#5435);
+#1636=VERTEX_POINT('',#5439);
+#1637=VERTEX_POINT('',#5441);
+#1638=VERTEX_POINT('',#5449);
+#1639=VERTEX_POINT('',#5450);
+#1640=VERTEX_POINT('',#5452);
+#1641=VERTEX_POINT('',#5454);
+#1642=VERTEX_POINT('',#5458);
+#1643=VERTEX_POINT('',#5460);
+#1644=VERTEX_POINT('',#5464);
+#1645=VERTEX_POINT('',#5466);
+#1646=VERTEX_POINT('',#5474);
+#1647=VERTEX_POINT('',#5475);
+#1648=VERTEX_POINT('',#5477);
+#1649=VERTEX_POINT('',#5479);
+#1650=VERTEX_POINT('',#5483);
+#1651=VERTEX_POINT('',#5485);
+#1652=VERTEX_POINT('',#5489);
+#1653=VERTEX_POINT('',#5491);
+#1654=VERTEX_POINT('',#5499);
+#1655=VERTEX_POINT('',#5500);
+#1656=VERTEX_POINT('',#5502);
+#1657=VERTEX_POINT('',#5504);
+#1658=VERTEX_POINT('',#5508);
+#1659=VERTEX_POINT('',#5510);
+#1660=VERTEX_POINT('',#5514);
+#1661=VERTEX_POINT('',#5516);
+#1662=VERTEX_POINT('',#5524);
+#1663=VERTEX_POINT('',#5525);
+#1664=VERTEX_POINT('',#5527);
+#1665=VERTEX_POINT('',#5529);
+#1666=VERTEX_POINT('',#5533);
+#1667=VERTEX_POINT('',#5535);
+#1668=VERTEX_POINT('',#5539);
+#1669=VERTEX_POINT('',#5541);
+#1670=VERTEX_POINT('',#5549);
+#1671=VERTEX_POINT('',#5551);
+#1672=VERTEX_POINT('',#5553);
+#1673=VERTEX_POINT('',#5555);
+#1674=VERTEX_POINT('',#5568);
+#1675=VERTEX_POINT('',#5570);
+#1676=VERTEX_POINT('',#5572);
+#1677=VERTEX_POINT('',#5574);
+#1678=VERTEX_POINT('',#5587);
+#1679=VERTEX_POINT('',#5589);
+#1680=VERTEX_POINT('',#5598);
+#1681=VERTEX_POINT('',#5600);
+#1682=VERTEX_POINT('',#5611);
+#1683=VERTEX_POINT('',#5613);
+#1684=VERTEX_POINT('',#5617);
+#1685=VERTEX_POINT('',#5618);
+#1686=VERTEX_POINT('',#5620);
+#1687=VERTEX_POINT('',#5622);
+#1688=VERTEX_POINT('',#5626);
+#1689=VERTEX_POINT('',#5627);
+#1690=VERTEX_POINT('',#5629);
+#1691=VERTEX_POINT('',#5631);
+#1692=VERTEX_POINT('',#5635);
+#1693=VERTEX_POINT('',#5637);
+#1694=VERTEX_POINT('',#5639);
+#1695=VERTEX_POINT('',#5641);
+#1696=VERTEX_POINT('',#5643);
+#1697=VERTEX_POINT('',#5645);
+#1698=VERTEX_POINT('',#5647);
+#1699=VERTEX_POINT('',#5649);
+#1700=VERTEX_POINT('',#5651);
+#1701=VERTEX_POINT('',#5653);
+#1702=VERTEX_POINT('',#5655);
+#1703=VERTEX_POINT('',#5657);
+#1704=VERTEX_POINT('',#5659);
+#1705=VERTEX_POINT('',#5661);
+#1706=VERTEX_POINT('',#5663);
+#1707=VERTEX_POINT('',#5665);
+#1708=VERTEX_POINT('',#5668);
+#1709=VERTEX_POINT('',#5670);
+#1710=VERTEX_POINT('',#5672);
+#1711=VERTEX_POINT('',#5674);
+#1712=VERTEX_POINT('',#5676);
+#1713=VERTEX_POINT('',#5678);
+#1714=VERTEX_POINT('',#5680);
+#1715=VERTEX_POINT('',#5682);
+#1716=VERTEX_POINT('',#5684);
+#1717=VERTEX_POINT('',#5686);
+#1718=VERTEX_POINT('',#5688);
+#1719=VERTEX_POINT('',#5690);
+#1720=VERTEX_POINT('',#5692);
+#1721=VERTEX_POINT('',#5694);
+#1722=VERTEX_POINT('',#5696);
+#1723=VERTEX_POINT('',#5698);
+#1724=VERTEX_POINT('',#5700);
+#1725=VERTEX_POINT('',#5702);
+#1726=VERTEX_POINT('',#5704);
+#1727=VERTEX_POINT('',#5706);
+#1728=VERTEX_POINT('',#5708);
+#1729=VERTEX_POINT('',#5710);
+#1730=VERTEX_POINT('',#5713);
+#1731=VERTEX_POINT('',#5715);
+#1732=VERTEX_POINT('',#5717);
+#1733=VERTEX_POINT('',#5719);
+#1734=VERTEX_POINT('',#5722);
+#1735=VERTEX_POINT('',#5724);
+#1736=VERTEX_POINT('',#5729);
+#1737=VERTEX_POINT('',#5731);
+#1738=VERTEX_POINT('',#5735);
+#1739=VERTEX_POINT('',#5873);
+#1740=VERTEX_POINT('',#5874);
+#1741=VERTEX_POINT('',#5935);
+#1742=VERTEX_POINT('',#5936);
+#1743=VERTEX_POINT('',#5941);
+#1744=VERTEX_POINT('',#5942);
+#1745=VERTEX_POINT('',#5947);
+#1746=VERTEX_POINT('',#6045);
+#1747=VERTEX_POINT('',#6083);
+#1748=VERTEX_POINT('',#6124);
+#1749=VERTEX_POINT('',#6125);
+#1750=VERTEX_POINT('',#6130);
+#1751=VERTEX_POINT('',#6132);
+#1752=VERTEX_POINT('',#6136);
+#1753=VERTEX_POINT('',#6141);
+#1754=VERTEX_POINT('',#6146);
+#1755=VERTEX_POINT('',#6153);
+#1756=VERTEX_POINT('',#6155);
+#1757=VERTEX_POINT('',#6157);
+#1758=VERTEX_POINT('',#6159);
+#1759=VERTEX_POINT('',#6161);
+#1760=VERTEX_POINT('',#6163);
+#1761=VERTEX_POINT('',#6165);
+#1762=VERTEX_POINT('',#6167);
+#1763=VERTEX_POINT('',#6169);
+#1764=VERTEX_POINT('',#6171);
+#1765=VERTEX_POINT('',#6173);
+#1766=VERTEX_POINT('',#6175);
+#1767=VERTEX_POINT('',#6177);
+#1768=VERTEX_POINT('',#6180);
+#1769=VERTEX_POINT('',#6181);
+#1770=VERTEX_POINT('',#6183);
+#1771=VERTEX_POINT('',#6185);
+#1772=VERTEX_POINT('',#6188);
+#1773=VERTEX_POINT('',#6189);
+#1774=VERTEX_POINT('',#6191);
+#1775=VERTEX_POINT('',#6193);
+#1776=VERTEX_POINT('',#6196);
+#1777=VERTEX_POINT('',#6197);
+#1778=VERTEX_POINT('',#6199);
+#1779=VERTEX_POINT('',#6201);
+#1780=VERTEX_POINT('',#6204);
+#1781=VERTEX_POINT('',#6205);
+#1782=VERTEX_POINT('',#6207);
+#1783=VERTEX_POINT('',#6209);
+#1784=VERTEX_POINT('',#6212);
+#1785=VERTEX_POINT('',#6213);
+#1786=VERTEX_POINT('',#6215);
+#1787=VERTEX_POINT('',#6217);
+#1788=VERTEX_POINT('',#6222);
+#1789=VERTEX_POINT('',#6226);
+#1790=VERTEX_POINT('',#6227);
+#1791=VERTEX_POINT('',#6229);
+#1792=VERTEX_POINT('',#6231);
+#1793=VERTEX_POINT('',#6275);
+#1794=VERTEX_POINT('',#6279);
+#1795=VERTEX_POINT('',#6282);
+#1796=VERTEX_POINT('',#6284);
+#1797=VERTEX_POINT('',#6289);
+#1798=VERTEX_POINT('',#6290);
+#1799=VERTEX_POINT('',#6295);
+#1800=VERTEX_POINT('',#6299);
+#1801=VERTEX_POINT('',#6305);
+#1802=VERTEX_POINT('',#6312);
+#1803=VERTEX_POINT('',#6318);
+#1804=VERTEX_POINT('',#6319);
+#1805=VERTEX_POINT('',#6326);
+#1806=VERTEX_POINT('',#6330);
+#1807=VERTEX_POINT('',#6334);
+#1808=VERTEX_POINT('',#6338);
+#1809=VERTEX_POINT('',#6355);
+#1810=VERTEX_POINT('',#6357);
+#1811=VERTEX_POINT('',#6369);
+#1812=VERTEX_POINT('',#6371);
+#1813=VERTEX_POINT('',#6376);
+#1814=VERTEX_POINT('',#6381);
+#1815=VERTEX_POINT('',#6383);
+#1816=VERTEX_POINT('',#6388);
+#1817=VERTEX_POINT('',#6390);
+#1818=VERTEX_POINT('',#6434);
+#1819=VERTEX_POINT('',#6467);
+#1820=VERTEX_POINT('',#6471);
+#1821=VERTEX_POINT('',#6475);
+#1822=VERTEX_POINT('',#6477);
+#1823=VERTEX_POINT('',#6507);
+#1824=VERTEX_POINT('',#6511);
+#1825=VERTEX_POINT('',#6515);
+#1826=VERTEX_POINT('',#6562);
+#1827=VERTEX_POINT('',#6563);
+#1828=VERTEX_POINT('',#6565);
+#1829=VERTEX_POINT('',#6953);
+#1830=VERTEX_POINT('',#6957);
+#1831=VERTEX_POINT('',#6968);
+#1832=VERTEX_POINT('',#6973);
+#1833=VERTEX_POINT('',#6978);
+#1834=VERTEX_POINT('',#6983);
+#1835=VERTEX_POINT('',#6988);
+#1836=VERTEX_POINT('',#6990);
+#1837=VERTEX_POINT('',#6994);
+#1838=VERTEX_POINT('',#6998);
+#1839=VERTEX_POINT('',#7004);
+#1840=VERTEX_POINT('',#7006);
+#1841=VERTEX_POINT('',#7010);
+#1842=VERTEX_POINT('',#7014);
+#1843=VERTEX_POINT('',#7020);
+#1844=VERTEX_POINT('',#7022);
+#1845=VERTEX_POINT('',#7026);
+#1846=VERTEX_POINT('',#7030);
+#1847=VERTEX_POINT('',#7036);
+#1848=VERTEX_POINT('',#7038);
+#1849=VERTEX_POINT('',#7042);
+#1850=VERTEX_POINT('',#7046);
+#1851=VERTEX_POINT('',#7052);
+#1852=VERTEX_POINT('',#7054);
+#1853=VERTEX_POINT('',#7058);
+#1854=VERTEX_POINT('',#7062);
+#1855=VERTEX_POINT('',#7068);
+#1856=VERTEX_POINT('',#7069);
+#1857=VERTEX_POINT('',#7071);
+#1858=VERTEX_POINT('',#7073);
+#1859=VERTEX_POINT('',#7077);
+#1860=VERTEX_POINT('',#7079);
+#1861=VERTEX_POINT('',#7083);
+#1862=VERTEX_POINT('',#7085);
+#1863=VERTEX_POINT('',#7093);
+#1864=VERTEX_POINT('',#7094);
+#1865=VERTEX_POINT('',#7096);
+#1866=VERTEX_POINT('',#7098);
+#1867=VERTEX_POINT('',#7102);
+#1868=VERTEX_POINT('',#7104);
+#1869=VERTEX_POINT('',#7108);
+#1870=VERTEX_POINT('',#7110);
+#1871=VERTEX_POINT('',#7118);
+#1872=VERTEX_POINT('',#7119);
+#1873=VERTEX_POINT('',#7121);
+#1874=VERTEX_POINT('',#7123);
+#1875=VERTEX_POINT('',#7127);
+#1876=VERTEX_POINT('',#7129);
+#1877=VERTEX_POINT('',#7133);
+#1878=VERTEX_POINT('',#7135);
+#1879=VERTEX_POINT('',#7143);
+#1880=VERTEX_POINT('',#7144);
+#1881=VERTEX_POINT('',#7146);
+#1882=VERTEX_POINT('',#7148);
+#1883=VERTEX_POINT('',#7152);
+#1884=VERTEX_POINT('',#7154);
+#1885=VERTEX_POINT('',#7158);
+#1886=VERTEX_POINT('',#7160);
+#1887=VERTEX_POINT('',#7168);
+#1888=VERTEX_POINT('',#7169);
+#1889=VERTEX_POINT('',#7171);
+#1890=VERTEX_POINT('',#7173);
+#1891=VERTEX_POINT('',#7177);
+#1892=VERTEX_POINT('',#7179);
+#1893=VERTEX_POINT('',#7183);
+#1894=VERTEX_POINT('',#7185);
+#1895=VERTEX_POINT('',#7193);
+#1896=VERTEX_POINT('',#7195);
+#1897=VERTEX_POINT('',#7200);
+#1898=VERTEX_POINT('',#7202);
+#1899=VERTEX_POINT('',#7207);
+#1900=VERTEX_POINT('',#7209);
+#1901=VERTEX_POINT('',#7214);
+#1902=VERTEX_POINT('',#7216);
+#1903=VERTEX_POINT('',#7221);
+#1904=VERTEX_POINT('',#7223);
+#1905=VERTEX_POINT('',#7228);
+#1906=VERTEX_POINT('',#7230);
+#1907=VERTEX_POINT('',#7235);
+#1908=VERTEX_POINT('',#7237);
+#1909=VERTEX_POINT('',#7244);
+#1910=VERTEX_POINT('',#7246);
+#1911=VERTEX_POINT('',#7250);
+#1912=VERTEX_POINT('',#7252);
+#1913=VERTEX_POINT('',#7256);
+#1914=VERTEX_POINT('',#7258);
+#1915=VERTEX_POINT('',#7262);
+#1916=VERTEX_POINT('',#7266);
+#1917=VERTEX_POINT('',#7270);
+#1918=VERTEX_POINT('',#7277);
+#1919=VERTEX_POINT('',#7283);
+#1920=VERTEX_POINT('',#7285);
+#1921=VERTEX_POINT('',#7287);
+#1922=VERTEX_POINT('',#7289);
+#1923=EDGE_CURVE('',#1610,#1611,#1577,.T.);
+#1924=EDGE_CURVE('',#1610,#1612,#1578,.T.);
+#1925=EDGE_CURVE('',#1612,#1613,#1579,.T.);
+#1926=EDGE_CURVE('',#1613,#1614,#1403,.T.);
+#1927=EDGE_CURVE('',#1611,#1614,#1580,.T.);
+#1928=EDGE_CURVE('',#1615,#1616,#1581,.T.);
+#1929=EDGE_CURVE('',#1615,#1615,#1582,.T.);
+#1930=EDGE_CURVE('',#1615,#1617,#1404,.T.);
+#1931=EDGE_CURVE('',#1618,#1617,#1583,.T.);
+#1932=EDGE_CURVE('',#1616,#1618,#1584,.T.);
+#1933=EDGE_CURVE('',#1619,#1620,#260,.T.);
+#1934=EDGE_CURVE('',#1621,#1619,#1585,.T.);
+#1935=EDGE_CURVE('',#1622,#1621,#1586,.T.);
+#1936=EDGE_CURVE('',#1623,#1622,#261,.T.);
+#1937=EDGE_CURVE('',#1624,#1623,#262,.T.);
+#1938=EDGE_CURVE('',#1625,#1624,#263,.T.);
+#1939=EDGE_CURVE('',#1626,#1625,#1587,.T.);
+#1940=EDGE_CURVE('',#1627,#1626,#1588,.T.);
+#1941=EDGE_CURVE('',#1628,#1627,#264,.T.);
+#1942=EDGE_CURVE('',#1620,#1628,#265,.T.);
+#1943=EDGE_CURVE('',#1628,#1620,#1405,.T.);
+#1944=EDGE_CURVE('',#1629,#1629,#1406,.T.);
+#1945=EDGE_CURVE('',#1619,#1627,#1407,.T.);
+#1946=EDGE_CURVE('',#1621,#1626,#1408,.T.);
+#1947=EDGE_CURVE('',#1630,#1631,#266,.T.);
+#1948=EDGE_CURVE('',#1630,#1632,#267,.T.);
+#1949=EDGE_CURVE('',#1632,#1633,#268,.T.);
+#1950=EDGE_CURVE('',#1631,#1633,#269,.T.);
+#1951=EDGE_CURVE('',#1634,#1630,#270,.T.);
+#1952=EDGE_CURVE('',#1634,#1635,#271,.T.);
+#1953=EDGE_CURVE('',#1635,#1632,#272,.T.);
+#1954=EDGE_CURVE('',#1636,#1634,#273,.T.);
+#1955=EDGE_CURVE('',#1636,#1637,#274,.T.);
+#1956=EDGE_CURVE('',#1637,#1635,#275,.T.);
+#1957=EDGE_CURVE('',#1631,#1636,#276,.T.);
+#1958=EDGE_CURVE('',#1633,#1637,#277,.T.);
+#1959=EDGE_CURVE('',#1638,#1639,#278,.T.);
+#1960=EDGE_CURVE('',#1638,#1640,#279,.T.);
+#1961=EDGE_CURVE('',#1640,#1641,#280,.T.);
+#1962=EDGE_CURVE('',#1639,#1641,#281,.T.);
+#1963=EDGE_CURVE('',#1642,#1638,#282,.T.);
+#1964=EDGE_CURVE('',#1642,#1643,#283,.T.);
+#1965=EDGE_CURVE('',#1643,#1640,#284,.T.);
+#1966=EDGE_CURVE('',#1644,#1642,#285,.T.);
+#1967=EDGE_CURVE('',#1644,#1645,#286,.T.);
+#1968=EDGE_CURVE('',#1645,#1643,#287,.T.);
+#1969=EDGE_CURVE('',#1639,#1644,#288,.T.);
+#1970=EDGE_CURVE('',#1641,#1645,#289,.T.);
+#1971=EDGE_CURVE('',#1646,#1647,#290,.T.);
+#1972=EDGE_CURVE('',#1646,#1648,#291,.T.);
+#1973=EDGE_CURVE('',#1648,#1649,#292,.T.);
+#1974=EDGE_CURVE('',#1647,#1649,#293,.T.);
+#1975=EDGE_CURVE('',#1650,#1646,#294,.T.);
+#1976=EDGE_CURVE('',#1650,#1651,#295,.T.);
+#1977=EDGE_CURVE('',#1651,#1648,#296,.T.);
+#1978=EDGE_CURVE('',#1652,#1650,#297,.T.);
+#1979=EDGE_CURVE('',#1652,#1653,#298,.T.);
+#1980=EDGE_CURVE('',#1653,#1651,#299,.T.);
+#1981=EDGE_CURVE('',#1647,#1652,#300,.T.);
+#1982=EDGE_CURVE('',#1649,#1653,#301,.T.);
+#1983=EDGE_CURVE('',#1654,#1655,#302,.T.);
+#1984=EDGE_CURVE('',#1654,#1656,#303,.T.);
+#1985=EDGE_CURVE('',#1656,#1657,#304,.T.);
+#1986=EDGE_CURVE('',#1655,#1657,#305,.T.);
+#1987=EDGE_CURVE('',#1658,#1654,#306,.T.);
+#1988=EDGE_CURVE('',#1658,#1659,#307,.T.);
+#1989=EDGE_CURVE('',#1659,#1656,#308,.T.);
+#1990=EDGE_CURVE('',#1660,#1658,#309,.T.);
+#1991=EDGE_CURVE('',#1660,#1661,#310,.T.);
+#1992=EDGE_CURVE('',#1661,#1659,#311,.T.);
+#1993=EDGE_CURVE('',#1655,#1660,#312,.T.);
+#1994=EDGE_CURVE('',#1657,#1661,#313,.T.);
+#1995=EDGE_CURVE('',#1662,#1663,#314,.T.);
+#1996=EDGE_CURVE('',#1662,#1664,#315,.T.);
+#1997=EDGE_CURVE('',#1664,#1665,#316,.T.);
+#1998=EDGE_CURVE('',#1663,#1665,#317,.T.);
+#1999=EDGE_CURVE('',#1666,#1662,#318,.T.);
+#2000=EDGE_CURVE('',#1666,#1667,#319,.T.);
+#2001=EDGE_CURVE('',#1667,#1664,#320,.T.);
+#2002=EDGE_CURVE('',#1668,#1666,#321,.T.);
+#2003=EDGE_CURVE('',#1668,#1669,#322,.T.);
+#2004=EDGE_CURVE('',#1669,#1667,#323,.T.);
+#2005=EDGE_CURVE('',#1663,#1668,#324,.T.);
+#2006=EDGE_CURVE('',#1665,#1669,#325,.T.);
+#2007=EDGE_CURVE('',#1670,#1670,#1409,.T.);
+#2008=EDGE_CURVE('',#1670,#1671,#326,.T.);
+#2009=EDGE_CURVE('',#1672,#1671,#1410,.T.);
+#2010=EDGE_CURVE('',#1673,#1672,#1589,.T.);
+#2011=EDGE_CURVE('',#1671,#1673,#1411,.T.);
+#2012=EDGE_CURVE('',#1674,#1674,#1412,.T.);
+#2013=EDGE_CURVE('',#1674,#1675,#327,.T.);
+#2014=EDGE_CURVE('',#1676,#1675,#1413,.T.);
+#2015=EDGE_CURVE('',#1677,#1676,#1590,.T.);
+#2016=EDGE_CURVE('',#1675,#1677,#1414,.T.);
+#2017=EDGE_CURVE('',#1678,#1673,#328,.T.);
+#2018=EDGE_CURVE('',#1679,#1678,#1591,.T.);
+#2019=EDGE_CURVE('',#1679,#1680,#329,.T.);
+#2020=EDGE_CURVE('',#1681,#1680,#1592,.T.);
+#2021=EDGE_CURVE('',#1676,#1681,#330,.T.);
+#2022=EDGE_CURVE('',#1682,#1677,#331,.T.);
+#2023=EDGE_CURVE('',#1683,#1682,#332,.T.);
+#2024=EDGE_CURVE('',#1672,#1683,#333,.T.);
+#2025=EDGE_CURVE('',#1684,#1685,#334,.T.);
+#2026=EDGE_CURVE('',#1686,#1684,#1415,.T.);
+#2027=EDGE_CURVE('',#1687,#1686,#335,.T.);
+#2028=EDGE_CURVE('',#1685,#1687,#1416,.T.);
+#2029=EDGE_CURVE('',#1688,#1689,#336,.T.);
+#2030=EDGE_CURVE('',#1690,#1688,#1417,.T.);
+#2031=EDGE_CURVE('',#1691,#1690,#337,.T.);
+#2032=EDGE_CURVE('',#1689,#1691,#1418,.T.);
+#2033=EDGE_CURVE('',#1686,#1692,#338,.T.);
+#2034=EDGE_CURVE('',#1692,#1693,#339,.T.);
+#2035=EDGE_CURVE('',#1693,#1694,#1419,.T.);
+#2036=EDGE_CURVE('',#1694,#1695,#1420,.T.);
+#2037=EDGE_CURVE('',#1695,#1696,#340,.T.);
+#2038=EDGE_CURVE('',#1696,#1697,#1421,.T.);
+#2039=EDGE_CURVE('',#1697,#1698,#1422,.T.);
+#2040=EDGE_CURVE('',#1698,#1699,#1423,.T.);
+#2041=EDGE_CURVE('',#1699,#1700,#1424,.T.);
+#2042=EDGE_CURVE('',#1700,#1701,#1425,.T.);
+#2043=EDGE_CURVE('',#1701,#1702,#1426,.T.);
+#2044=EDGE_CURVE('',#1702,#1703,#1427,.T.);
+#2045=EDGE_CURVE('',#1703,#1704,#341,.T.);
+#2046=EDGE_CURVE('',#1704,#1705,#1428,.T.);
+#2047=EDGE_CURVE('',#1705,#1706,#1429,.T.);
+#2048=EDGE_CURVE('',#1706,#1707,#342,.T.);
+#2049=EDGE_CURVE('',#1707,#1691,#343,.T.);
+#2050=EDGE_CURVE('',#1690,#1708,#344,.T.);
+#2051=EDGE_CURVE('',#1709,#1708,#1430,.T.);
+#2052=EDGE_CURVE('',#1709,#1710,#345,.T.);
+#2053=EDGE_CURVE('',#1711,#1710,#1431,.T.);
+#2054=EDGE_CURVE('',#1711,#1712,#1432,.T.);
+#2055=EDGE_CURVE('',#1712,#1713,#1433,.T.);
+#2056=EDGE_CURVE('',#1713,#1714,#1434,.T.);
+#2057=EDGE_CURVE('',#1714,#1715,#1435,.T.);
+#2058=EDGE_CURVE('',#1715,#1716,#346,.T.);
+#2059=EDGE_CURVE('',#1716,#1717,#1436,.T.);
+#2060=EDGE_CURVE('',#1717,#1718,#1437,.T.);
+#2061=EDGE_CURVE('',#1718,#1719,#1438,.T.);
+#2062=EDGE_CURVE('',#1719,#1720,#1439,.T.);
+#2063=EDGE_CURVE('',#1720,#1721,#1440,.T.);
+#2064=EDGE_CURVE('',#1721,#1722,#347,.T.);
+#2065=EDGE_CURVE('',#1722,#1723,#1441,.T.);
+#2066=EDGE_CURVE('',#1723,#1724,#1442,.T.);
+#2067=EDGE_CURVE('',#1724,#1725,#1443,.T.);
+#2068=EDGE_CURVE('',#1725,#1726,#1444,.T.);
+#2069=EDGE_CURVE('',#1727,#1726,#1445,.T.);
+#2070=EDGE_CURVE('',#1727,#1728,#348,.T.);
+#2071=EDGE_CURVE('',#1729,#1728,#1446,.T.);
+#2072=EDGE_CURVE('',#1729,#1687,#349,.T.);
+#2073=EDGE_CURVE('',#1730,#1730,#1447,.T.);
+#2074=EDGE_CURVE('',#1731,#1731,#1448,.T.);
+#2075=EDGE_CURVE('',#1732,#1732,#1449,.T.);
+#2076=EDGE_CURVE('',#1733,#1733,#1450,.T.);
+#2077=EDGE_CURVE('',#1734,#1729,#350,.T.);
+#2078=EDGE_CURVE('',#1735,#1734,#351,.T.);
+#2079=EDGE_CURVE('',#1708,#1735,#352,.T.);
+#2080=EDGE_CURVE('',#1685,#1688,#353,.T.);
+#2081=EDGE_CURVE('',#1682,#1736,#1451,.F.);
+#2082=EDGE_CURVE('',#1737,#1682,#1452,.F.);
+#2083=EDGE_CURVE('',#1736,#1737,#1453,.F.);
+#2084=EDGE_CURVE('',#1681,#1738,#1454,.T.);
+#2085=EDGE_CURVE('',#1738,#1737,#354,.T.);
+#2086=EDGE_CURVE('',#1739,#1740,#1593,.T.);
+#2087=EDGE_CURVE('',#1740,#1738,#1594,.T.);
+#2088=EDGE_CURVE('',#1680,#1739,#1595,.T.);
+#2089=EDGE_CURVE('',#1741,#1742,#1455,.T.);
+#2090=EDGE_CURVE('',#1742,#1736,#355,.T.);
+#2091=EDGE_CURVE('',#1737,#1741,#356,.T.);
+#2092=EDGE_CURVE('',#1743,#1744,#1456,.F.);
+#2093=EDGE_CURVE('',#1683,#1743,#1457,.F.);
+#2094=EDGE_CURVE('',#1744,#1683,#1458,.F.);
+#2095=EDGE_CURVE('',#1743,#1745,#357,.T.);
+#2096=EDGE_CURVE('',#1745,#1678,#1459,.T.);
+#2097=EDGE_CURVE('',#1746,#1679,#1596,.T.);
+#2098=EDGE_CURVE('',#1745,#1747,#1597,.T.);
+#2099=EDGE_CURVE('',#1747,#1746,#1598,.T.);
+#2100=EDGE_CURVE('',#1736,#1744,#358,.T.);
+#2101=EDGE_CURVE('',#1748,#1749,#1460,.T.);
+#2102=EDGE_CURVE('',#1749,#1743,#359,.T.);
+#2103=EDGE_CURVE('',#1744,#1748,#360,.T.);
+#2104=EDGE_CURVE('',#1750,#1738,#1461,.T.);
+#2105=EDGE_CURVE('',#1751,#1750,#361,.T.);
+#2106=EDGE_CURVE('',#1751,#1741,#362,.T.);
+#2107=EDGE_CURVE('',#1752,#1740,#1599,.F.);
+#2108=EDGE_CURVE('',#1752,#1753,#1462,.T.);
+#2109=EDGE_CURVE('',#1750,#1753,#1463,.T.);
+#2110=EDGE_CURVE('',#1746,#1739,#363,.T.);
+#2111=EDGE_CURVE('',#1754,#1747,#1600,.T.);
+#2112=EDGE_CURVE('',#1755,#1754,#1464,.T.);
+#2113=EDGE_CURVE('',#1756,#1755,#1465,.T.);
+#2114=EDGE_CURVE('',#1757,#1756,#1466,.T.);
+#2115=EDGE_CURVE('',#1758,#1757,#364,.T.);
+#2116=EDGE_CURVE('',#1759,#1758,#1467,.T.);
+#2117=EDGE_CURVE('',#1760,#1759,#1468,.T.);
+#2118=EDGE_CURVE('',#1761,#1760,#1469,.T.);
+#2119=EDGE_CURVE('',#1762,#1761,#365,.T.);
+#2120=EDGE_CURVE('',#1763,#1762,#366,.T.);
+#2121=EDGE_CURVE('',#1764,#1763,#367,.T.);
+#2122=EDGE_CURVE('',#1765,#1764,#1470,.T.);
+#2123=EDGE_CURVE('',#1766,#1765,#1471,.T.);
+#2124=EDGE_CURVE('',#1767,#1766,#1472,.T.);
+#2125=EDGE_CURVE('',#1752,#1767,#368,.T.);
+#2126=EDGE_CURVE('',#1768,#1769,#369,.T.);
+#2127=EDGE_CURVE('',#1769,#1770,#370,.T.);
+#2128=EDGE_CURVE('',#1770,#1771,#371,.T.);
+#2129=EDGE_CURVE('',#1771,#1768,#372,.T.);
+#2130=EDGE_CURVE('',#1772,#1773,#373,.T.);
+#2131=EDGE_CURVE('',#1773,#1774,#374,.T.);
+#2132=EDGE_CURVE('',#1774,#1775,#375,.T.);
+#2133=EDGE_CURVE('',#1775,#1772,#376,.T.);
+#2134=EDGE_CURVE('',#1776,#1777,#377,.T.);
+#2135=EDGE_CURVE('',#1777,#1778,#378,.T.);
+#2136=EDGE_CURVE('',#1778,#1779,#379,.T.);
+#2137=EDGE_CURVE('',#1779,#1776,#380,.T.);
+#2138=EDGE_CURVE('',#1780,#1781,#381,.T.);
+#2139=EDGE_CURVE('',#1781,#1782,#382,.T.);
+#2140=EDGE_CURVE('',#1782,#1783,#383,.T.);
+#2141=EDGE_CURVE('',#1783,#1780,#384,.T.);
+#2142=EDGE_CURVE('',#1784,#1785,#385,.T.);
+#2143=EDGE_CURVE('',#1785,#1786,#386,.T.);
+#2144=EDGE_CURVE('',#1786,#1787,#387,.T.);
+#2145=EDGE_CURVE('',#1787,#1784,#388,.T.);
+#2146=EDGE_CURVE('',#1753,#1788,#389,.T.);
+#2147=EDGE_CURVE('',#1788,#1751,#1473,.T.);
+#2148=EDGE_CURVE('',#1789,#1790,#1474,.F.);
+#2149=EDGE_CURVE('',#1789,#1791,#390,.T.);
+#2150=EDGE_CURVE('',#1791,#1792,#1475,.T.);
+#2151=EDGE_CURVE('',#1792,#1790,#391,.T.);
+#2152=EDGE_CURVE('',#1745,#1792,#1601,.T.);
+#2153=EDGE_CURVE('',#1791,#1754,#1602,.T.);
+#2154=EDGE_CURVE('',#1791,#1793,#1476,.T.);
+#2155=EDGE_CURVE('',#1755,#1793,#1477,.T.);
+#2156=EDGE_CURVE('',#1789,#1794,#1478,.T.);
+#2157=EDGE_CURVE('',#1794,#1721,#392,.T.);
+#2158=EDGE_CURVE('',#1720,#1795,#393,.T.);
+#2159=EDGE_CURVE('',#1795,#1796,#1479,.T.);
+#2160=EDGE_CURVE('',#1796,#1719,#394,.T.);
+#2161=EDGE_CURVE('',#1793,#1718,#395,.T.);
+#2162=EDGE_CURVE('',#1797,#1798,#1480,.F.);
+#2163=EDGE_CURVE('',#1765,#1797,#1481,.T.);
+#2164=EDGE_CURVE('',#1798,#1764,#1482,.T.);
+#2165=EDGE_CURVE('',#1767,#1799,#1483,.T.);
+#2166=EDGE_CURVE('',#1799,#1753,#396,.T.);
+#2167=EDGE_CURVE('',#1766,#1800,#1484,.T.);
+#2168=EDGE_CURVE('',#1800,#1799,#1485,.T.);
+#2169=EDGE_CURVE('',#1797,#1800,#1486,.T.);
+#2170=EDGE_CURVE('',#1801,#1734,#1487,.F.);
+#2171=EDGE_CURVE('',#1763,#1801,#1488,.F.);
+#2172=EDGE_CURVE('',#1734,#1763,#1489,.F.);
+#2173=EDGE_CURVE('',#1801,#1798,#397,.T.);
+#2174=EDGE_CURVE('',#1735,#1802,#1490,.F.);
+#2175=EDGE_CURVE('',#1762,#1735,#1491,.F.);
+#2176=EDGE_CURVE('',#1802,#1762,#1492,.F.);
+#2177=EDGE_CURVE('',#1803,#1804,#1493,.F.);
+#2178=EDGE_CURVE('',#1761,#1803,#1494,.T.);
+#2179=EDGE_CURVE('',#1804,#1760,#1495,.T.);
+#2180=EDGE_CURVE('',#1803,#1802,#398,.T.);
+#2181=EDGE_CURVE('',#1759,#1805,#1496,.T.);
+#2182=EDGE_CURVE('',#1805,#1804,#1497,.T.);
+#2183=EDGE_CURVE('',#1758,#1806,#1498,.T.);
+#2184=EDGE_CURVE('',#1806,#1805,#1499,.T.);
+#2185=EDGE_CURVE('',#1757,#1807,#1500,.T.);
+#2186=EDGE_CURVE('',#1807,#1806,#399,.T.);
+#2187=EDGE_CURVE('',#1756,#1808,#1501,.T.);
+#2188=EDGE_CURVE('',#1808,#1807,#1502,.T.);
+#2189=EDGE_CURVE('',#1793,#1808,#1503,.T.);
+#2190=EDGE_CURVE('',#1710,#1803,#400,.T.);
+#2191=EDGE_CURVE('',#1804,#1711,#401,.T.);
+#2192=EDGE_CURVE('',#1802,#1709,#402,.T.);
+#2193=EDGE_CURVE('',#1728,#1801,#403,.T.);
+#2194=EDGE_CURVE('',#1726,#1797,#404,.T.);
+#2195=EDGE_CURVE('',#1798,#1727,#405,.T.);
+#2196=EDGE_CURVE('',#1800,#1725,#406,.T.);
+#2197=EDGE_CURVE('',#1724,#1809,#407,.T.);
+#2198=EDGE_CURVE('',#1809,#1810,#1504,.T.);
+#2199=EDGE_CURVE('',#1810,#1723,#408,.T.);
+#2200=EDGE_CURVE('',#1799,#1722,#409,.T.);
+#2201=EDGE_CURVE('',#1790,#1749,#410,.T.);
+#2202=EDGE_CURVE('',#1794,#1788,#411,.T.);
+#2203=EDGE_CURVE('',#1742,#1748,#412,.T.);
+#2204=EDGE_CURVE('',#1811,#1811,#1505,.T.);
+#2205=EDGE_CURVE('',#1811,#1812,#413,.T.);
+#2206=EDGE_CURVE('',#1812,#1812,#1506,.T.);
+#2207=EDGE_CURVE('',#1629,#1813,#414,.T.);
+#2208=EDGE_CURVE('',#1813,#1813,#1507,.T.);
+#2209=EDGE_CURVE('',#1814,#1814,#1508,.T.);
+#2210=EDGE_CURVE('',#1814,#1815,#415,.T.);
+#2211=EDGE_CURVE('',#1815,#1815,#1509,.T.);
+#2212=EDGE_CURVE('',#1816,#1816,#1510,.T.);
+#2213=EDGE_CURVE('',#1816,#1817,#416,.T.);
+#2214=EDGE_CURVE('',#1817,#1817,#1511,.T.);
+#2215=EDGE_CURVE('',#1618,#1818,#1512,.T.);
+#2216=EDGE_CURVE('',#1617,#1616,#1603,.T.);
+#2217=EDGE_CURVE('',#1818,#1818,#1604,.T.);
+#2218=EDGE_CURVE('',#1818,#1819,#417,.T.);
+#2219=EDGE_CURVE('',#1819,#1819,#1513,.T.);
+#2220=EDGE_CURVE('',#1820,#1615,#418,.T.);
+#2221=EDGE_CURVE('',#1820,#1820,#1514,.T.);
+#2222=EDGE_CURVE('',#1821,#1821,#1515,.T.);
+#2223=EDGE_CURVE('',#1821,#1822,#1516,.T.);
+#2224=EDGE_CURVE('',#1822,#1822,#1517,.T.);
+#2225=EDGE_CURVE('',#1823,#1823,#1518,.T.);
+#2226=EDGE_CURVE('',#1823,#1822,#1519,.T.);
+#2227=EDGE_CURVE('',#1821,#1824,#419,.T.);
+#2228=EDGE_CURVE('',#1824,#1824,#1520,.T.);
+#2229=EDGE_CURVE('',#1825,#1825,#1521,.T.);
+#2230=EDGE_CURVE('',#1825,#1823,#420,.T.);
+#2231=EDGE_CURVE('',#1826,#1827,#1522,.T.);
+#2232=EDGE_CURVE('',#1827,#1828,#1605,.T.);
+#2233=EDGE_CURVE('',#1828,#1827,#1606,.T.);
+#2234=EDGE_CURVE('',#1826,#1611,#1607,.T.);
+#2235=EDGE_CURVE('',#1614,#1826,#1608,.T.);
+#2236=EDGE_CURVE('',#1613,#1610,#1609,.T.);
+#2237=EDGE_CURVE('',#1828,#1829,#421,.T.);
+#2238=EDGE_CURVE('',#1829,#1829,#1523,.T.);
+#2239=EDGE_CURVE('',#1830,#1830,#1524,.T.);
+#2240=EDGE_CURVE('',#1830,#1612,#422,.T.);
+#2241=EDGE_CURVE('',#1625,#1622,#1525,.T.);
+#2242=EDGE_CURVE('',#1623,#1624,#1526,.T.);
+#2243=EDGE_CURVE('',#1733,#1831,#423,.T.);
+#2244=EDGE_CURVE('',#1831,#1831,#1527,.T.);
+#2245=EDGE_CURVE('',#1732,#1832,#424,.T.);
+#2246=EDGE_CURVE('',#1832,#1832,#1528,.T.);
+#2247=EDGE_CURVE('',#1731,#1833,#425,.T.);
+#2248=EDGE_CURVE('',#1833,#1833,#1529,.T.);
+#2249=EDGE_CURVE('',#1730,#1834,#426,.T.);
+#2250=EDGE_CURVE('',#1834,#1834,#1530,.T.);
+#2251=EDGE_CURVE('',#1835,#1770,#427,.T.);
+#2252=EDGE_CURVE('',#1836,#1835,#428,.T.);
+#2253=EDGE_CURVE('',#1836,#1771,#429,.T.);
+#2254=EDGE_CURVE('',#1837,#1836,#430,.T.);
+#2255=EDGE_CURVE('',#1837,#1768,#431,.T.);
+#2256=EDGE_CURVE('',#1838,#1837,#432,.T.);
+#2257=EDGE_CURVE('',#1838,#1769,#433,.T.);
+#2258=EDGE_CURVE('',#1835,#1838,#434,.T.);
+#2259=EDGE_CURVE('',#1839,#1774,#435,.T.);
+#2260=EDGE_CURVE('',#1840,#1839,#436,.T.);
+#2261=EDGE_CURVE('',#1840,#1775,#437,.T.);
+#2262=EDGE_CURVE('',#1841,#1840,#438,.T.);
+#2263=EDGE_CURVE('',#1841,#1772,#439,.T.);
+#2264=EDGE_CURVE('',#1842,#1841,#440,.T.);
+#2265=EDGE_CURVE('',#1842,#1773,#441,.T.);
+#2266=EDGE_CURVE('',#1839,#1842,#442,.T.);
+#2267=EDGE_CURVE('',#1843,#1778,#443,.T.);
+#2268=EDGE_CURVE('',#1844,#1843,#444,.T.);
+#2269=EDGE_CURVE('',#1844,#1779,#445,.T.);
+#2270=EDGE_CURVE('',#1845,#1844,#446,.T.);
+#2271=EDGE_CURVE('',#1845,#1776,#447,.T.);
+#2272=EDGE_CURVE('',#1846,#1845,#448,.T.);
+#2273=EDGE_CURVE('',#1846,#1777,#449,.T.);
+#2274=EDGE_CURVE('',#1843,#1846,#450,.T.);
+#2275=EDGE_CURVE('',#1847,#1782,#451,.T.);
+#2276=EDGE_CURVE('',#1848,#1847,#452,.T.);
+#2277=EDGE_CURVE('',#1848,#1783,#453,.T.);
+#2278=EDGE_CURVE('',#1849,#1848,#454,.T.);
+#2279=EDGE_CURVE('',#1849,#1780,#455,.T.);
+#2280=EDGE_CURVE('',#1850,#1849,#456,.T.);
+#2281=EDGE_CURVE('',#1850,#1781,#457,.T.);
+#2282=EDGE_CURVE('',#1847,#1850,#458,.T.);
+#2283=EDGE_CURVE('',#1851,#1786,#459,.T.);
+#2284=EDGE_CURVE('',#1852,#1851,#460,.T.);
+#2285=EDGE_CURVE('',#1852,#1787,#461,.T.);
+#2286=EDGE_CURVE('',#1853,#1852,#462,.T.);
+#2287=EDGE_CURVE('',#1853,#1784,#463,.T.);
+#2288=EDGE_CURVE('',#1854,#1853,#464,.T.);
+#2289=EDGE_CURVE('',#1854,#1785,#465,.T.);
+#2290=EDGE_CURVE('',#1851,#1854,#466,.T.);
+#2291=EDGE_CURVE('',#1855,#1856,#467,.T.);
+#2292=EDGE_CURVE('',#1855,#1857,#468,.T.);
+#2293=EDGE_CURVE('',#1857,#1858,#469,.T.);
+#2294=EDGE_CURVE('',#1856,#1858,#470,.T.);
+#2295=EDGE_CURVE('',#1859,#1855,#471,.T.);
+#2296=EDGE_CURVE('',#1859,#1860,#472,.T.);
+#2297=EDGE_CURVE('',#1860,#1857,#473,.T.);
+#2298=EDGE_CURVE('',#1861,#1859,#474,.T.);
+#2299=EDGE_CURVE('',#1861,#1862,#475,.T.);
+#2300=EDGE_CURVE('',#1862,#1860,#476,.T.);
+#2301=EDGE_CURVE('',#1856,#1861,#477,.T.);
+#2302=EDGE_CURVE('',#1858,#1862,#478,.T.);
+#2303=EDGE_CURVE('',#1863,#1864,#479,.T.);
+#2304=EDGE_CURVE('',#1863,#1865,#480,.T.);
+#2305=EDGE_CURVE('',#1865,#1866,#481,.T.);
+#2306=EDGE_CURVE('',#1864,#1866,#482,.T.);
+#2307=EDGE_CURVE('',#1867,#1863,#483,.T.);
+#2308=EDGE_CURVE('',#1867,#1868,#484,.T.);
+#2309=EDGE_CURVE('',#1868,#1865,#485,.T.);
+#2310=EDGE_CURVE('',#1869,#1867,#486,.T.);
+#2311=EDGE_CURVE('',#1869,#1870,#487,.T.);
+#2312=EDGE_CURVE('',#1870,#1868,#488,.T.);
+#2313=EDGE_CURVE('',#1864,#1869,#489,.T.);
+#2314=EDGE_CURVE('',#1866,#1870,#490,.T.);
+#2315=EDGE_CURVE('',#1871,#1872,#491,.T.);
+#2316=EDGE_CURVE('',#1871,#1873,#492,.T.);
+#2317=EDGE_CURVE('',#1873,#1874,#493,.T.);
+#2318=EDGE_CURVE('',#1872,#1874,#494,.T.);
+#2319=EDGE_CURVE('',#1875,#1871,#495,.T.);
+#2320=EDGE_CURVE('',#1875,#1876,#496,.T.);
+#2321=EDGE_CURVE('',#1876,#1873,#497,.T.);
+#2322=EDGE_CURVE('',#1877,#1875,#498,.T.);
+#2323=EDGE_CURVE('',#1877,#1878,#499,.T.);
+#2324=EDGE_CURVE('',#1878,#1876,#500,.T.);
+#2325=EDGE_CURVE('',#1872,#1877,#501,.T.);
+#2326=EDGE_CURVE('',#1874,#1878,#502,.T.);
+#2327=EDGE_CURVE('',#1879,#1880,#503,.T.);
+#2328=EDGE_CURVE('',#1879,#1881,#504,.T.);
+#2329=EDGE_CURVE('',#1881,#1882,#505,.T.);
+#2330=EDGE_CURVE('',#1880,#1882,#506,.T.);
+#2331=EDGE_CURVE('',#1883,#1879,#507,.T.);
+#2332=EDGE_CURVE('',#1883,#1884,#508,.T.);
+#2333=EDGE_CURVE('',#1884,#1881,#509,.T.);
+#2334=EDGE_CURVE('',#1885,#1883,#510,.T.);
+#2335=EDGE_CURVE('',#1885,#1886,#511,.T.);
+#2336=EDGE_CURVE('',#1886,#1884,#512,.T.);
+#2337=EDGE_CURVE('',#1880,#1885,#513,.T.);
+#2338=EDGE_CURVE('',#1882,#1886,#514,.T.);
+#2339=EDGE_CURVE('',#1887,#1888,#515,.T.);
+#2340=EDGE_CURVE('',#1887,#1889,#516,.T.);
+#2341=EDGE_CURVE('',#1889,#1890,#517,.T.);
+#2342=EDGE_CURVE('',#1888,#1890,#518,.T.);
+#2343=EDGE_CURVE('',#1891,#1887,#519,.T.);
+#2344=EDGE_CURVE('',#1891,#1892,#520,.T.);
+#2345=EDGE_CURVE('',#1892,#1889,#521,.T.);
+#2346=EDGE_CURVE('',#1893,#1891,#522,.T.);
+#2347=EDGE_CURVE('',#1893,#1894,#523,.T.);
+#2348=EDGE_CURVE('',#1894,#1892,#524,.T.);
+#2349=EDGE_CURVE('',#1888,#1893,#525,.T.);
+#2350=EDGE_CURVE('',#1890,#1894,#526,.T.);
+#2351=EDGE_CURVE('',#1895,#1895,#1531,.T.);
+#2352=EDGE_CURVE('',#1895,#1896,#527,.T.);
+#2353=EDGE_CURVE('',#1896,#1896,#1532,.T.);
+#2354=EDGE_CURVE('',#1897,#1897,#1533,.T.);
+#2355=EDGE_CURVE('',#1897,#1898,#528,.T.);
+#2356=EDGE_CURVE('',#1898,#1898,#1534,.T.);
+#2357=EDGE_CURVE('',#1899,#1899,#1535,.T.);
+#2358=EDGE_CURVE('',#1899,#1900,#529,.T.);
+#2359=EDGE_CURVE('',#1900,#1900,#1536,.T.);
+#2360=EDGE_CURVE('',#1901,#1901,#1537,.T.);
+#2361=EDGE_CURVE('',#1901,#1902,#530,.T.);
+#2362=EDGE_CURVE('',#1902,#1902,#1538,.T.);
+#2363=EDGE_CURVE('',#1903,#1903,#1539,.T.);
+#2364=EDGE_CURVE('',#1903,#1904,#531,.T.);
+#2365=EDGE_CURVE('',#1904,#1904,#1540,.T.);
+#2366=EDGE_CURVE('',#1695,#1905,#532,.T.);
+#2367=EDGE_CURVE('',#1906,#1694,#533,.T.);
+#2368=EDGE_CURVE('',#1905,#1906,#1541,.T.);
+#2369=EDGE_CURVE('',#1907,#1701,#534,.T.);
+#2370=EDGE_CURVE('',#1908,#1907,#1542,.T.);
+#2371=EDGE_CURVE('',#1702,#1908,#535,.T.);
+#2372=EDGE_CURVE('',#1796,#1795,#1543,.T.);
+#2373=EDGE_CURVE('',#1909,#1697,#536,.T.);
+#2374=EDGE_CURVE('',#1910,#1909,#1544,.T.);
+#2375=EDGE_CURVE('',#1698,#1910,#537,.T.);
+#2376=EDGE_CURVE('',#1714,#1911,#538,.T.);
+#2377=EDGE_CURVE('',#1912,#1713,#539,.T.);
+#2378=EDGE_CURVE('',#1911,#1912,#1545,.T.);
+#2379=EDGE_CURVE('',#1913,#1704,#540,.T.);
+#2380=EDGE_CURVE('',#1914,#1913,#1546,.T.);
+#2381=EDGE_CURVE('',#1705,#1914,#541,.T.);
+#2382=EDGE_CURVE('',#1915,#1905,#542,.F.);
+#2383=EDGE_CURVE('',#1915,#1696,#543,.T.);
+#2384=EDGE_CURVE('',#1916,#1908,#1547,.F.);
+#2385=EDGE_CURVE('',#1916,#1703,#544,.T.);
+#2386=EDGE_CURVE('',#1917,#1700,#545,.T.);
+#2387=EDGE_CURVE('',#1907,#1917,#1548,.F.);
+#2388=EDGE_CURVE('',#1808,#1717,#546,.T.);
+#2389=EDGE_CURVE('',#1807,#1716,#547,.T.);
+#2390=EDGE_CURVE('',#1918,#1910,#1549,.F.);
+#2391=EDGE_CURVE('',#1918,#1699,#548,.T.);
+#2392=EDGE_CURVE('',#1909,#1915,#1550,.F.);
+#2393=EDGE_CURVE('',#1906,#1919,#1551,.F.);
+#2394=EDGE_CURVE('',#1919,#1920,#549,.F.);
+#2395=EDGE_CURVE('',#1920,#1921,#550,.F.);
+#2396=EDGE_CURVE('',#1921,#1922,#551,.F.);
+#2397=EDGE_CURVE('',#1922,#1914,#1552,.F.);
+#2398=EDGE_CURVE('',#1913,#1916,#552,.F.);
+#2399=EDGE_CURVE('',#1917,#1918,#1553,.F.);
+#2400=EDGE_CURVE('',#1689,#1684,#553,.T.);
+#2401=EDGE_CURVE('',#1806,#1715,#554,.T.);
+#2402=EDGE_CURVE('',#1805,#1712,#555,.T.);
+#2403=EDGE_CURVE('',#1922,#1706,#556,.T.);
+#2404=EDGE_CURVE('',#1921,#1707,#557,.F.);
+#2405=EDGE_CURVE('',#1920,#1692,#558,.F.);
+#2406=EDGE_CURVE('',#1919,#1693,#559,.T.);
+#2407=ORIENTED_EDGE('',*,*,#1923,.F.);
+#2408=ORIENTED_EDGE('',*,*,#1924,.T.);
+#2409=ORIENTED_EDGE('',*,*,#1925,.T.);
+#2410=ORIENTED_EDGE('',*,*,#1926,.T.);
+#2411=ORIENTED_EDGE('',*,*,#1927,.F.);
+#2412=ORIENTED_EDGE('',*,*,#1928,.F.);
+#2413=ORIENTED_EDGE('',*,*,#1929,.T.);
+#2414=ORIENTED_EDGE('',*,*,#1930,.T.);
+#2415=ORIENTED_EDGE('',*,*,#1931,.F.);
+#2416=ORIENTED_EDGE('',*,*,#1932,.F.);
+#2417=ORIENTED_EDGE('',*,*,#1933,.F.);
+#2418=ORIENTED_EDGE('',*,*,#1934,.F.);
+#2419=ORIENTED_EDGE('',*,*,#1935,.F.);
+#2420=ORIENTED_EDGE('',*,*,#1936,.F.);
+#2421=ORIENTED_EDGE('',*,*,#1937,.F.);
+#2422=ORIENTED_EDGE('',*,*,#1938,.F.);
+#2423=ORIENTED_EDGE('',*,*,#1939,.F.);
+#2424=ORIENTED_EDGE('',*,*,#1940,.F.);
+#2425=ORIENTED_EDGE('',*,*,#1941,.F.);
+#2426=ORIENTED_EDGE('',*,*,#1942,.F.);
+#2427=ORIENTED_EDGE('',*,*,#1942,.T.);
+#2428=ORIENTED_EDGE('',*,*,#1943,.T.);
+#2429=ORIENTED_EDGE('',*,*,#1944,.T.);
+#2430=ORIENTED_EDGE('',*,*,#1933,.T.);
+#2431=ORIENTED_EDGE('',*,*,#1943,.F.);
+#2432=ORIENTED_EDGE('',*,*,#1941,.T.);
+#2433=ORIENTED_EDGE('',*,*,#1945,.F.);
+#2434=ORIENTED_EDGE('',*,*,#1934,.T.);
+#2435=ORIENTED_EDGE('',*,*,#1945,.T.);
+#2436=ORIENTED_EDGE('',*,*,#1940,.T.);
+#2437=ORIENTED_EDGE('',*,*,#1946,.F.);
+#2438=ORIENTED_EDGE('',*,*,#1947,.F.);
+#2439=ORIENTED_EDGE('',*,*,#1948,.T.);
+#2440=ORIENTED_EDGE('',*,*,#1949,.T.);
+#2441=ORIENTED_EDGE('',*,*,#1950,.F.);
+#2442=ORIENTED_EDGE('',*,*,#1951,.F.);
+#2443=ORIENTED_EDGE('',*,*,#1952,.T.);
+#2444=ORIENTED_EDGE('',*,*,#1953,.T.);
+#2445=ORIENTED_EDGE('',*,*,#1948,.F.);
+#2446=ORIENTED_EDGE('',*,*,#1954,.F.);
+#2447=ORIENTED_EDGE('',*,*,#1955,.T.);
+#2448=ORIENTED_EDGE('',*,*,#1956,.T.);
+#2449=ORIENTED_EDGE('',*,*,#1952,.F.);
+#2450=ORIENTED_EDGE('',*,*,#1957,.F.);
+#2451=ORIENTED_EDGE('',*,*,#1950,.T.);
+#2452=ORIENTED_EDGE('',*,*,#1958,.T.);
+#2453=ORIENTED_EDGE('',*,*,#1955,.F.);
+#2454=ORIENTED_EDGE('',*,*,#1958,.F.);
+#2455=ORIENTED_EDGE('',*,*,#1949,.F.);
+#2456=ORIENTED_EDGE('',*,*,#1953,.F.);
+#2457=ORIENTED_EDGE('',*,*,#1956,.F.);
+#2458=ORIENTED_EDGE('',*,*,#1959,.F.);
+#2459=ORIENTED_EDGE('',*,*,#1960,.T.);
+#2460=ORIENTED_EDGE('',*,*,#1961,.T.);
+#2461=ORIENTED_EDGE('',*,*,#1962,.F.);
+#2462=ORIENTED_EDGE('',*,*,#1963,.F.);
+#2463=ORIENTED_EDGE('',*,*,#1964,.T.);
+#2464=ORIENTED_EDGE('',*,*,#1965,.T.);
+#2465=ORIENTED_EDGE('',*,*,#1960,.F.);
+#2466=ORIENTED_EDGE('',*,*,#1966,.F.);
+#2467=ORIENTED_EDGE('',*,*,#1967,.T.);
+#2468=ORIENTED_EDGE('',*,*,#1968,.T.);
+#2469=ORIENTED_EDGE('',*,*,#1964,.F.);
+#2470=ORIENTED_EDGE('',*,*,#1969,.F.);
+#2471=ORIENTED_EDGE('',*,*,#1962,.T.);
+#2472=ORIENTED_EDGE('',*,*,#1970,.T.);
+#2473=ORIENTED_EDGE('',*,*,#1967,.F.);
+#2474=ORIENTED_EDGE('',*,*,#1970,.F.);
+#2475=ORIENTED_EDGE('',*,*,#1961,.F.);
+#2476=ORIENTED_EDGE('',*,*,#1965,.F.);
+#2477=ORIENTED_EDGE('',*,*,#1968,.F.);
+#2478=ORIENTED_EDGE('',*,*,#1971,.F.);
+#2479=ORIENTED_EDGE('',*,*,#1972,.T.);
+#2480=ORIENTED_EDGE('',*,*,#1973,.T.);
+#2481=ORIENTED_EDGE('',*,*,#1974,.F.);
+#2482=ORIENTED_EDGE('',*,*,#1975,.F.);
+#2483=ORIENTED_EDGE('',*,*,#1976,.T.);
+#2484=ORIENTED_EDGE('',*,*,#1977,.T.);
+#2485=ORIENTED_EDGE('',*,*,#1972,.F.);
+#2486=ORIENTED_EDGE('',*,*,#1978,.F.);
+#2487=ORIENTED_EDGE('',*,*,#1979,.T.);
+#2488=ORIENTED_EDGE('',*,*,#1980,.T.);
+#2489=ORIENTED_EDGE('',*,*,#1976,.F.);
+#2490=ORIENTED_EDGE('',*,*,#1981,.F.);
+#2491=ORIENTED_EDGE('',*,*,#1974,.T.);
+#2492=ORIENTED_EDGE('',*,*,#1982,.T.);
+#2493=ORIENTED_EDGE('',*,*,#1979,.F.);
+#2494=ORIENTED_EDGE('',*,*,#1982,.F.);
+#2495=ORIENTED_EDGE('',*,*,#1973,.F.);
+#2496=ORIENTED_EDGE('',*,*,#1977,.F.);
+#2497=ORIENTED_EDGE('',*,*,#1980,.F.);
+#2498=ORIENTED_EDGE('',*,*,#1983,.F.);
+#2499=ORIENTED_EDGE('',*,*,#1984,.T.);
+#2500=ORIENTED_EDGE('',*,*,#1985,.T.);
+#2501=ORIENTED_EDGE('',*,*,#1986,.F.);
+#2502=ORIENTED_EDGE('',*,*,#1987,.F.);
+#2503=ORIENTED_EDGE('',*,*,#1988,.T.);
+#2504=ORIENTED_EDGE('',*,*,#1989,.T.);
+#2505=ORIENTED_EDGE('',*,*,#1984,.F.);
+#2506=ORIENTED_EDGE('',*,*,#1990,.F.);
+#2507=ORIENTED_EDGE('',*,*,#1991,.T.);
+#2508=ORIENTED_EDGE('',*,*,#1992,.T.);
+#2509=ORIENTED_EDGE('',*,*,#1988,.F.);
+#2510=ORIENTED_EDGE('',*,*,#1993,.F.);
+#2511=ORIENTED_EDGE('',*,*,#1986,.T.);
+#2512=ORIENTED_EDGE('',*,*,#1994,.T.);
+#2513=ORIENTED_EDGE('',*,*,#1991,.F.);
+#2514=ORIENTED_EDGE('',*,*,#1994,.F.);
+#2515=ORIENTED_EDGE('',*,*,#1985,.F.);
+#2516=ORIENTED_EDGE('',*,*,#1989,.F.);
+#2517=ORIENTED_EDGE('',*,*,#1992,.F.);
+#2518=ORIENTED_EDGE('',*,*,#1995,.F.);
+#2519=ORIENTED_EDGE('',*,*,#1996,.T.);
+#2520=ORIENTED_EDGE('',*,*,#1997,.T.);
+#2521=ORIENTED_EDGE('',*,*,#1998,.F.);
+#2522=ORIENTED_EDGE('',*,*,#1999,.F.);
+#2523=ORIENTED_EDGE('',*,*,#2000,.T.);
+#2524=ORIENTED_EDGE('',*,*,#2001,.T.);
+#2525=ORIENTED_EDGE('',*,*,#1996,.F.);
+#2526=ORIENTED_EDGE('',*,*,#2002,.F.);
+#2527=ORIENTED_EDGE('',*,*,#2003,.T.);
+#2528=ORIENTED_EDGE('',*,*,#2004,.T.);
+#2529=ORIENTED_EDGE('',*,*,#2000,.F.);
+#2530=ORIENTED_EDGE('',*,*,#2005,.F.);
+#2531=ORIENTED_EDGE('',*,*,#1998,.T.);
+#2532=ORIENTED_EDGE('',*,*,#2006,.T.);
+#2533=ORIENTED_EDGE('',*,*,#2003,.F.);
+#2534=ORIENTED_EDGE('',*,*,#2006,.F.);
+#2535=ORIENTED_EDGE('',*,*,#1997,.F.);
+#2536=ORIENTED_EDGE('',*,*,#2001,.F.);
+#2537=ORIENTED_EDGE('',*,*,#2004,.F.);
+#2538=ORIENTED_EDGE('',*,*,#2007,.F.);
+#2539=ORIENTED_EDGE('',*,*,#2008,.T.);
+#2540=ORIENTED_EDGE('',*,*,#2009,.F.);
+#2541=ORIENTED_EDGE('',*,*,#2010,.F.);
+#2542=ORIENTED_EDGE('',*,*,#2011,.F.);
+#2543=ORIENTED_EDGE('',*,*,#2008,.F.);
+#2544=ORIENTED_EDGE('',*,*,#2012,.F.);
+#2545=ORIENTED_EDGE('',*,*,#2013,.T.);
+#2546=ORIENTED_EDGE('',*,*,#2014,.F.);
+#2547=ORIENTED_EDGE('',*,*,#2015,.F.);
+#2548=ORIENTED_EDGE('',*,*,#2016,.F.);
+#2549=ORIENTED_EDGE('',*,*,#2013,.F.);
+#2550=ORIENTED_EDGE('',*,*,#2009,.T.);
+#2551=ORIENTED_EDGE('',*,*,#2011,.T.);
+#2552=ORIENTED_EDGE('',*,*,#2017,.F.);
+#2553=ORIENTED_EDGE('',*,*,#2018,.F.);
+#2554=ORIENTED_EDGE('',*,*,#2019,.T.);
+#2555=ORIENTED_EDGE('',*,*,#2020,.F.);
+#2556=ORIENTED_EDGE('',*,*,#2021,.F.);
+#2557=ORIENTED_EDGE('',*,*,#2014,.T.);
+#2558=ORIENTED_EDGE('',*,*,#2016,.T.);
+#2559=ORIENTED_EDGE('',*,*,#2022,.F.);
+#2560=ORIENTED_EDGE('',*,*,#2023,.F.);
+#2561=ORIENTED_EDGE('',*,*,#2024,.F.);
+#2562=ORIENTED_EDGE('',*,*,#2025,.F.);
+#2563=ORIENTED_EDGE('',*,*,#2026,.F.);
+#2564=ORIENTED_EDGE('',*,*,#2027,.F.);
+#2565=ORIENTED_EDGE('',*,*,#2028,.F.);
+#2566=ORIENTED_EDGE('',*,*,#2029,.F.);
+#2567=ORIENTED_EDGE('',*,*,#2030,.F.);
+#2568=ORIENTED_EDGE('',*,*,#2031,.F.);
+#2569=ORIENTED_EDGE('',*,*,#2032,.F.);
+#2570=ORIENTED_EDGE('',*,*,#2027,.T.);
+#2571=ORIENTED_EDGE('',*,*,#2033,.T.);
+#2572=ORIENTED_EDGE('',*,*,#2034,.T.);
+#2573=ORIENTED_EDGE('',*,*,#2035,.T.);
+#2574=ORIENTED_EDGE('',*,*,#2036,.T.);
+#2575=ORIENTED_EDGE('',*,*,#2037,.T.);
+#2576=ORIENTED_EDGE('',*,*,#2038,.T.);
+#2577=ORIENTED_EDGE('',*,*,#2039,.T.);
+#2578=ORIENTED_EDGE('',*,*,#2040,.T.);
+#2579=ORIENTED_EDGE('',*,*,#2041,.T.);
+#2580=ORIENTED_EDGE('',*,*,#2042,.T.);
+#2581=ORIENTED_EDGE('',*,*,#2043,.T.);
+#2582=ORIENTED_EDGE('',*,*,#2044,.T.);
+#2583=ORIENTED_EDGE('',*,*,#2045,.T.);
+#2584=ORIENTED_EDGE('',*,*,#2046,.T.);
+#2585=ORIENTED_EDGE('',*,*,#2047,.T.);
+#2586=ORIENTED_EDGE('',*,*,#2048,.T.);
+#2587=ORIENTED_EDGE('',*,*,#2049,.T.);
+#2588=ORIENTED_EDGE('',*,*,#2031,.T.);
+#2589=ORIENTED_EDGE('',*,*,#2050,.T.);
+#2590=ORIENTED_EDGE('',*,*,#2051,.F.);
+#2591=ORIENTED_EDGE('',*,*,#2052,.T.);
+#2592=ORIENTED_EDGE('',*,*,#2053,.F.);
+#2593=ORIENTED_EDGE('',*,*,#2054,.T.);
+#2594=ORIENTED_EDGE('',*,*,#2055,.T.);
+#2595=ORIENTED_EDGE('',*,*,#2056,.T.);
+#2596=ORIENTED_EDGE('',*,*,#2057,.T.);
+#2597=ORIENTED_EDGE('',*,*,#2058,.T.);
+#2598=ORIENTED_EDGE('',*,*,#2059,.T.);
+#2599=ORIENTED_EDGE('',*,*,#2060,.T.);
+#2600=ORIENTED_EDGE('',*,*,#2061,.T.);
+#2601=ORIENTED_EDGE('',*,*,#2062,.T.);
+#2602=ORIENTED_EDGE('',*,*,#2063,.T.);
+#2603=ORIENTED_EDGE('',*,*,#2064,.T.);
+#2604=ORIENTED_EDGE('',*,*,#2065,.T.);
+#2605=ORIENTED_EDGE('',*,*,#2066,.T.);
+#2606=ORIENTED_EDGE('',*,*,#2067,.T.);
+#2607=ORIENTED_EDGE('',*,*,#2068,.T.);
+#2608=ORIENTED_EDGE('',*,*,#2069,.F.);
+#2609=ORIENTED_EDGE('',*,*,#2070,.T.);
+#2610=ORIENTED_EDGE('',*,*,#2071,.F.);
+#2611=ORIENTED_EDGE('',*,*,#2072,.T.);
+#2612=ORIENTED_EDGE('',*,*,#2073,.T.);
+#2613=ORIENTED_EDGE('',*,*,#2074,.T.);
+#2614=ORIENTED_EDGE('',*,*,#2075,.T.);
+#2615=ORIENTED_EDGE('',*,*,#2076,.T.);
+#2616=ORIENTED_EDGE('',*,*,#2028,.T.);
+#2617=ORIENTED_EDGE('',*,*,#2072,.F.);
+#2618=ORIENTED_EDGE('',*,*,#2077,.F.);
+#2619=ORIENTED_EDGE('',*,*,#2078,.F.);
+#2620=ORIENTED_EDGE('',*,*,#2079,.F.);
+#2621=ORIENTED_EDGE('',*,*,#2050,.F.);
+#2622=ORIENTED_EDGE('',*,*,#2030,.T.);
+#2623=ORIENTED_EDGE('',*,*,#2080,.F.);
+#2624=ORIENTED_EDGE('',*,*,#2081,.F.);
+#2625=ORIENTED_EDGE('',*,*,#2082,.F.);
+#2626=ORIENTED_EDGE('',*,*,#2083,.F.);
+#2627=ORIENTED_EDGE('',*,*,#2015,.T.);
+#2628=ORIENTED_EDGE('',*,*,#2021,.T.);
+#2629=ORIENTED_EDGE('',*,*,#2084,.T.);
+#2630=ORIENTED_EDGE('',*,*,#2085,.T.);
+#2631=ORIENTED_EDGE('',*,*,#2082,.T.);
+#2632=ORIENTED_EDGE('',*,*,#2022,.T.);
+#2633=ORIENTED_EDGE('',*,*,#2086,.T.);
+#2634=ORIENTED_EDGE('',*,*,#2087,.T.);
+#2635=ORIENTED_EDGE('',*,*,#2084,.F.);
+#2636=ORIENTED_EDGE('',*,*,#2020,.T.);
+#2637=ORIENTED_EDGE('',*,*,#2088,.T.);
+#2638=ORIENTED_EDGE('',*,*,#2089,.T.);
+#2639=ORIENTED_EDGE('',*,*,#2090,.T.);
+#2640=ORIENTED_EDGE('',*,*,#2083,.T.);
+#2641=ORIENTED_EDGE('',*,*,#2091,.T.);
+#2642=ORIENTED_EDGE('',*,*,#2092,.F.);
+#2643=ORIENTED_EDGE('',*,*,#2093,.F.);
+#2644=ORIENTED_EDGE('',*,*,#2094,.F.);
+#2645=ORIENTED_EDGE('',*,*,#2010,.T.);
+#2646=ORIENTED_EDGE('',*,*,#2024,.T.);
+#2647=ORIENTED_EDGE('',*,*,#2093,.T.);
+#2648=ORIENTED_EDGE('',*,*,#2095,.T.);
+#2649=ORIENTED_EDGE('',*,*,#2096,.T.);
+#2650=ORIENTED_EDGE('',*,*,#2017,.T.);
+#2651=ORIENTED_EDGE('',*,*,#2097,.T.);
+#2652=ORIENTED_EDGE('',*,*,#2018,.T.);
+#2653=ORIENTED_EDGE('',*,*,#2096,.F.);
+#2654=ORIENTED_EDGE('',*,*,#2098,.T.);
+#2655=ORIENTED_EDGE('',*,*,#2099,.T.);
+#2656=ORIENTED_EDGE('',*,*,#2081,.T.);
+#2657=ORIENTED_EDGE('',*,*,#2100,.T.);
+#2658=ORIENTED_EDGE('',*,*,#2094,.T.);
+#2659=ORIENTED_EDGE('',*,*,#2023,.T.);
+#2660=ORIENTED_EDGE('',*,*,#2101,.T.);
+#2661=ORIENTED_EDGE('',*,*,#2102,.T.);
+#2662=ORIENTED_EDGE('',*,*,#2092,.T.);
+#2663=ORIENTED_EDGE('',*,*,#2103,.T.);
+#2664=ORIENTED_EDGE('',*,*,#2091,.F.);
+#2665=ORIENTED_EDGE('',*,*,#2085,.F.);
+#2666=ORIENTED_EDGE('',*,*,#2104,.F.);
+#2667=ORIENTED_EDGE('',*,*,#2105,.F.);
+#2668=ORIENTED_EDGE('',*,*,#2106,.T.);
+#2669=ORIENTED_EDGE('',*,*,#2087,.F.);
+#2670=ORIENTED_EDGE('',*,*,#2107,.F.);
+#2671=ORIENTED_EDGE('',*,*,#2108,.T.);
+#2672=ORIENTED_EDGE('',*,*,#2109,.F.);
+#2673=ORIENTED_EDGE('',*,*,#2104,.T.);
+#2674=ORIENTED_EDGE('',*,*,#2086,.F.);
+#2675=ORIENTED_EDGE('',*,*,#2110,.F.);
+#2676=ORIENTED_EDGE('',*,*,#2099,.F.);
+#2677=ORIENTED_EDGE('',*,*,#2111,.F.);
+#2678=ORIENTED_EDGE('',*,*,#2112,.F.);
+#2679=ORIENTED_EDGE('',*,*,#2113,.F.);
+#2680=ORIENTED_EDGE('',*,*,#2114,.F.);
+#2681=ORIENTED_EDGE('',*,*,#2115,.F.);
+#2682=ORIENTED_EDGE('',*,*,#2116,.F.);
+#2683=ORIENTED_EDGE('',*,*,#2117,.F.);
+#2684=ORIENTED_EDGE('',*,*,#2118,.F.);
+#2685=ORIENTED_EDGE('',*,*,#2119,.F.);
+#2686=ORIENTED_EDGE('',*,*,#2120,.F.);
+#2687=ORIENTED_EDGE('',*,*,#2121,.F.);
+#2688=ORIENTED_EDGE('',*,*,#2122,.F.);
+#2689=ORIENTED_EDGE('',*,*,#2123,.F.);
+#2690=ORIENTED_EDGE('',*,*,#2124,.F.);
+#2691=ORIENTED_EDGE('',*,*,#2125,.F.);
+#2692=ORIENTED_EDGE('',*,*,#2107,.T.);
+#2693=ORIENTED_EDGE('',*,*,#2126,.T.);
+#2694=ORIENTED_EDGE('',*,*,#2127,.T.);
+#2695=ORIENTED_EDGE('',*,*,#2128,.T.);
+#2696=ORIENTED_EDGE('',*,*,#2129,.T.);
+#2697=ORIENTED_EDGE('',*,*,#2130,.T.);
+#2698=ORIENTED_EDGE('',*,*,#2131,.T.);
+#2699=ORIENTED_EDGE('',*,*,#2132,.T.);
+#2700=ORIENTED_EDGE('',*,*,#2133,.T.);
+#2701=ORIENTED_EDGE('',*,*,#2134,.T.);
+#2702=ORIENTED_EDGE('',*,*,#2135,.T.);
+#2703=ORIENTED_EDGE('',*,*,#2136,.T.);
+#2704=ORIENTED_EDGE('',*,*,#2137,.T.);
+#2705=ORIENTED_EDGE('',*,*,#2138,.T.);
+#2706=ORIENTED_EDGE('',*,*,#2139,.T.);
+#2707=ORIENTED_EDGE('',*,*,#2140,.T.);
+#2708=ORIENTED_EDGE('',*,*,#2141,.T.);
+#2709=ORIENTED_EDGE('',*,*,#2142,.T.);
+#2710=ORIENTED_EDGE('',*,*,#2143,.T.);
+#2711=ORIENTED_EDGE('',*,*,#2144,.T.);
+#2712=ORIENTED_EDGE('',*,*,#2145,.T.);
+#2713=ORIENTED_EDGE('',*,*,#2088,.F.);
+#2714=ORIENTED_EDGE('',*,*,#2019,.F.);
+#2715=ORIENTED_EDGE('',*,*,#2097,.F.);
+#2716=ORIENTED_EDGE('',*,*,#2110,.T.);
+#2717=ORIENTED_EDGE('',*,*,#2109,.T.);
+#2718=ORIENTED_EDGE('',*,*,#2146,.T.);
+#2719=ORIENTED_EDGE('',*,*,#2147,.T.);
+#2720=ORIENTED_EDGE('',*,*,#2105,.T.);
+#2721=ORIENTED_EDGE('',*,*,#2148,.F.);
+#2722=ORIENTED_EDGE('',*,*,#2149,.T.);
+#2723=ORIENTED_EDGE('',*,*,#2150,.T.);
+#2724=ORIENTED_EDGE('',*,*,#2151,.T.);
+#2725=ORIENTED_EDGE('',*,*,#2098,.F.);
+#2726=ORIENTED_EDGE('',*,*,#2152,.T.);
+#2727=ORIENTED_EDGE('',*,*,#2150,.F.);
+#2728=ORIENTED_EDGE('',*,*,#2153,.T.);
+#2729=ORIENTED_EDGE('',*,*,#2111,.T.);
+#2730=ORIENTED_EDGE('',*,*,#2153,.F.);
+#2731=ORIENTED_EDGE('',*,*,#2154,.T.);
+#2732=ORIENTED_EDGE('',*,*,#2155,.F.);
+#2733=ORIENTED_EDGE('',*,*,#2112,.T.);
+#2734=ORIENTED_EDGE('',*,*,#2149,.F.);
+#2735=ORIENTED_EDGE('',*,*,#2156,.T.);
+#2736=ORIENTED_EDGE('',*,*,#2157,.T.);
+#2737=ORIENTED_EDGE('',*,*,#2063,.F.);
+#2738=ORIENTED_EDGE('',*,*,#2158,.T.);
+#2739=ORIENTED_EDGE('',*,*,#2159,.T.);
+#2740=ORIENTED_EDGE('',*,*,#2160,.T.);
+#2741=ORIENTED_EDGE('',*,*,#2061,.F.);
+#2742=ORIENTED_EDGE('',*,*,#2161,.F.);
+#2743=ORIENTED_EDGE('',*,*,#2154,.F.);
+#2744=ORIENTED_EDGE('',*,*,#2162,.F.);
+#2745=ORIENTED_EDGE('',*,*,#2163,.F.);
+#2746=ORIENTED_EDGE('',*,*,#2122,.T.);
+#2747=ORIENTED_EDGE('',*,*,#2164,.F.);
+#2748=ORIENTED_EDGE('',*,*,#2108,.F.);
+#2749=ORIENTED_EDGE('',*,*,#2125,.T.);
+#2750=ORIENTED_EDGE('',*,*,#2165,.T.);
+#2751=ORIENTED_EDGE('',*,*,#2166,.T.);
+#2752=ORIENTED_EDGE('',*,*,#2167,.T.);
+#2753=ORIENTED_EDGE('',*,*,#2168,.T.);
+#2754=ORIENTED_EDGE('',*,*,#2165,.F.);
+#2755=ORIENTED_EDGE('',*,*,#2124,.T.);
+#2756=ORIENTED_EDGE('',*,*,#2163,.T.);
+#2757=ORIENTED_EDGE('',*,*,#2169,.T.);
+#2758=ORIENTED_EDGE('',*,*,#2167,.F.);
+#2759=ORIENTED_EDGE('',*,*,#2123,.T.);
+#2760=ORIENTED_EDGE('',*,*,#2170,.F.);
+#2761=ORIENTED_EDGE('',*,*,#2171,.F.);
+#2762=ORIENTED_EDGE('',*,*,#2172,.F.);
+#2763=ORIENTED_EDGE('',*,*,#2171,.T.);
+#2764=ORIENTED_EDGE('',*,*,#2173,.T.);
+#2765=ORIENTED_EDGE('',*,*,#2164,.T.);
+#2766=ORIENTED_EDGE('',*,*,#2121,.T.);
+#2767=ORIENTED_EDGE('',*,*,#2174,.F.);
+#2768=ORIENTED_EDGE('',*,*,#2175,.F.);
+#2769=ORIENTED_EDGE('',*,*,#2176,.F.);
+#2770=ORIENTED_EDGE('',*,*,#2175,.T.);
+#2771=ORIENTED_EDGE('',*,*,#2078,.T.);
+#2772=ORIENTED_EDGE('',*,*,#2172,.T.);
+#2773=ORIENTED_EDGE('',*,*,#2120,.T.);
+#2774=ORIENTED_EDGE('',*,*,#2177,.F.);
+#2775=ORIENTED_EDGE('',*,*,#2178,.F.);
+#2776=ORIENTED_EDGE('',*,*,#2118,.T.);
+#2777=ORIENTED_EDGE('',*,*,#2179,.F.);
+#2778=ORIENTED_EDGE('',*,*,#2178,.T.);
+#2779=ORIENTED_EDGE('',*,*,#2180,.T.);
+#2780=ORIENTED_EDGE('',*,*,#2176,.T.);
+#2781=ORIENTED_EDGE('',*,*,#2119,.T.);
+#2782=ORIENTED_EDGE('',*,*,#2181,.T.);
+#2783=ORIENTED_EDGE('',*,*,#2182,.T.);
+#2784=ORIENTED_EDGE('',*,*,#2179,.T.);
+#2785=ORIENTED_EDGE('',*,*,#2117,.T.);
+#2786=ORIENTED_EDGE('',*,*,#2183,.T.);
+#2787=ORIENTED_EDGE('',*,*,#2184,.T.);
+#2788=ORIENTED_EDGE('',*,*,#2181,.F.);
+#2789=ORIENTED_EDGE('',*,*,#2116,.T.);
+#2790=ORIENTED_EDGE('',*,*,#2185,.T.);
+#2791=ORIENTED_EDGE('',*,*,#2186,.T.);
+#2792=ORIENTED_EDGE('',*,*,#2183,.F.);
+#2793=ORIENTED_EDGE('',*,*,#2115,.T.);
+#2794=ORIENTED_EDGE('',*,*,#2187,.T.);
+#2795=ORIENTED_EDGE('',*,*,#2188,.T.);
+#2796=ORIENTED_EDGE('',*,*,#2185,.F.);
+#2797=ORIENTED_EDGE('',*,*,#2114,.T.);
+#2798=ORIENTED_EDGE('',*,*,#2155,.T.);
+#2799=ORIENTED_EDGE('',*,*,#2189,.T.);
+#2800=ORIENTED_EDGE('',*,*,#2187,.F.);
+#2801=ORIENTED_EDGE('',*,*,#2113,.T.);
+#2802=ORIENTED_EDGE('',*,*,#2053,.T.);
+#2803=ORIENTED_EDGE('',*,*,#2190,.T.);
+#2804=ORIENTED_EDGE('',*,*,#2177,.T.);
+#2805=ORIENTED_EDGE('',*,*,#2191,.T.);
+#2806=ORIENTED_EDGE('',*,*,#2051,.T.);
+#2807=ORIENTED_EDGE('',*,*,#2079,.T.);
+#2808=ORIENTED_EDGE('',*,*,#2174,.T.);
+#2809=ORIENTED_EDGE('',*,*,#2192,.T.);
+#2810=ORIENTED_EDGE('',*,*,#2071,.T.);
+#2811=ORIENTED_EDGE('',*,*,#2193,.T.);
+#2812=ORIENTED_EDGE('',*,*,#2170,.T.);
+#2813=ORIENTED_EDGE('',*,*,#2077,.T.);
+#2814=ORIENTED_EDGE('',*,*,#2069,.T.);
+#2815=ORIENTED_EDGE('',*,*,#2194,.T.);
+#2816=ORIENTED_EDGE('',*,*,#2162,.T.);
+#2817=ORIENTED_EDGE('',*,*,#2195,.T.);
+#2818=ORIENTED_EDGE('',*,*,#2168,.F.);
+#2819=ORIENTED_EDGE('',*,*,#2196,.T.);
+#2820=ORIENTED_EDGE('',*,*,#2067,.F.);
+#2821=ORIENTED_EDGE('',*,*,#2197,.T.);
+#2822=ORIENTED_EDGE('',*,*,#2198,.T.);
+#2823=ORIENTED_EDGE('',*,*,#2199,.T.);
+#2824=ORIENTED_EDGE('',*,*,#2065,.F.);
+#2825=ORIENTED_EDGE('',*,*,#2200,.F.);
+#2826=ORIENTED_EDGE('',*,*,#2169,.F.);
+#2827=ORIENTED_EDGE('',*,*,#2194,.F.);
+#2828=ORIENTED_EDGE('',*,*,#2068,.F.);
+#2829=ORIENTED_EDGE('',*,*,#2196,.F.);
+#2830=ORIENTED_EDGE('',*,*,#2102,.F.);
+#2831=ORIENTED_EDGE('',*,*,#2201,.F.);
+#2832=ORIENTED_EDGE('',*,*,#2151,.F.);
+#2833=ORIENTED_EDGE('',*,*,#2152,.F.);
+#2834=ORIENTED_EDGE('',*,*,#2095,.F.);
+#2835=ORIENTED_EDGE('',*,*,#2089,.F.);
+#2836=ORIENTED_EDGE('',*,*,#2106,.F.);
+#2837=ORIENTED_EDGE('',*,*,#2147,.F.);
+#2838=ORIENTED_EDGE('',*,*,#2202,.F.);
+#2839=ORIENTED_EDGE('',*,*,#2156,.F.);
+#2840=ORIENTED_EDGE('',*,*,#2148,.T.);
+#2841=ORIENTED_EDGE('',*,*,#2201,.T.);
+#2842=ORIENTED_EDGE('',*,*,#2101,.F.);
+#2843=ORIENTED_EDGE('',*,*,#2203,.F.);
+#2844=ORIENTED_EDGE('',*,*,#2007,.T.);
+#2845=ORIENTED_EDGE('',*,*,#2012,.T.);
+#2846=ORIENTED_EDGE('',*,*,#2090,.F.);
+#2847=ORIENTED_EDGE('',*,*,#2203,.T.);
+#2848=ORIENTED_EDGE('',*,*,#2103,.F.);
+#2849=ORIENTED_EDGE('',*,*,#2100,.F.);
+#2850=ORIENTED_EDGE('',*,*,#2204,.F.);
+#2851=ORIENTED_EDGE('',*,*,#2205,.T.);
+#2852=ORIENTED_EDGE('',*,*,#2206,.T.);
+#2853=ORIENTED_EDGE('',*,*,#2205,.F.);
+#2854=ORIENTED_EDGE('',*,*,#2206,.F.);
+#2855=ORIENTED_EDGE('',*,*,#1944,.F.);
+#2856=ORIENTED_EDGE('',*,*,#2207,.T.);
+#2857=ORIENTED_EDGE('',*,*,#2208,.T.);
+#2858=ORIENTED_EDGE('',*,*,#2207,.F.);
+#2859=ORIENTED_EDGE('',*,*,#2208,.F.);
+#2860=ORIENTED_EDGE('',*,*,#2209,.F.);
+#2861=ORIENTED_EDGE('',*,*,#2210,.T.);
+#2862=ORIENTED_EDGE('',*,*,#2211,.T.);
+#2863=ORIENTED_EDGE('',*,*,#2210,.F.);
+#2864=ORIENTED_EDGE('',*,*,#2211,.F.);
+#2865=ORIENTED_EDGE('',*,*,#2212,.F.);
+#2866=ORIENTED_EDGE('',*,*,#2213,.T.);
+#2867=ORIENTED_EDGE('',*,*,#2214,.T.);
+#2868=ORIENTED_EDGE('',*,*,#2213,.F.);
+#2869=ORIENTED_EDGE('',*,*,#2214,.F.);
+#2870=ORIENTED_EDGE('',*,*,#2215,.F.);
+#2871=ORIENTED_EDGE('',*,*,#1931,.T.);
+#2872=ORIENTED_EDGE('',*,*,#2216,.T.);
+#2873=ORIENTED_EDGE('',*,*,#1932,.T.);
+#2874=ORIENTED_EDGE('',*,*,#2215,.T.);
+#2875=ORIENTED_EDGE('',*,*,#2217,.T.);
+#2876=ORIENTED_EDGE('',*,*,#1928,.T.);
+#2877=ORIENTED_EDGE('',*,*,#2216,.F.);
+#2878=ORIENTED_EDGE('',*,*,#1930,.F.);
+#2879=ORIENTED_EDGE('',*,*,#2218,.T.);
+#2880=ORIENTED_EDGE('',*,*,#2219,.F.);
+#2881=ORIENTED_EDGE('',*,*,#2218,.F.);
+#2882=ORIENTED_EDGE('',*,*,#2217,.F.);
+#2883=ORIENTED_EDGE('',*,*,#1929,.F.);
+#2884=ORIENTED_EDGE('',*,*,#2220,.F.);
+#2885=ORIENTED_EDGE('',*,*,#2221,.F.);
+#2886=ORIENTED_EDGE('',*,*,#2220,.T.);
+#2887=ORIENTED_EDGE('',*,*,#2222,.T.);
+#2888=ORIENTED_EDGE('',*,*,#2223,.T.);
+#2889=ORIENTED_EDGE('',*,*,#2224,.T.);
+#2890=ORIENTED_EDGE('',*,*,#2223,.F.);
+#2891=ORIENTED_EDGE('',*,*,#2225,.T.);
+#2892=ORIENTED_EDGE('',*,*,#2226,.T.);
+#2893=ORIENTED_EDGE('',*,*,#2224,.F.);
+#2894=ORIENTED_EDGE('',*,*,#2226,.F.);
+#2895=ORIENTED_EDGE('',*,*,#2222,.F.);
+#2896=ORIENTED_EDGE('',*,*,#2227,.T.);
+#2897=ORIENTED_EDGE('',*,*,#2228,.F.);
+#2898=ORIENTED_EDGE('',*,*,#2227,.F.);
+#2899=ORIENTED_EDGE('',*,*,#2229,.F.);
+#2900=ORIENTED_EDGE('',*,*,#2230,.T.);
+#2901=ORIENTED_EDGE('',*,*,#2225,.F.);
+#2902=ORIENTED_EDGE('',*,*,#2230,.F.);
+#2903=ORIENTED_EDGE('',*,*,#2231,.T.);
+#2904=ORIENTED_EDGE('',*,*,#2232,.T.);
+#2905=ORIENTED_EDGE('',*,*,#2233,.T.);
+#2906=ORIENTED_EDGE('',*,*,#2231,.F.);
+#2907=ORIENTED_EDGE('',*,*,#2234,.T.);
+#2908=ORIENTED_EDGE('',*,*,#1927,.T.);
+#2909=ORIENTED_EDGE('',*,*,#2235,.T.);
+#2910=ORIENTED_EDGE('',*,*,#1923,.T.);
+#2911=ORIENTED_EDGE('',*,*,#2234,.F.);
+#2912=ORIENTED_EDGE('',*,*,#2235,.F.);
+#2913=ORIENTED_EDGE('',*,*,#1926,.F.);
+#2914=ORIENTED_EDGE('',*,*,#2236,.T.);
+#2915=ORIENTED_EDGE('',*,*,#2232,.F.);
+#2916=ORIENTED_EDGE('',*,*,#2233,.F.);
+#2917=ORIENTED_EDGE('',*,*,#2237,.T.);
+#2918=ORIENTED_EDGE('',*,*,#2238,.F.);
+#2919=ORIENTED_EDGE('',*,*,#2237,.F.);
+#2920=ORIENTED_EDGE('',*,*,#2239,.F.);
+#2921=ORIENTED_EDGE('',*,*,#2240,.T.);
+#2922=ORIENTED_EDGE('',*,*,#1924,.F.);
+#2923=ORIENTED_EDGE('',*,*,#2236,.F.);
+#2924=ORIENTED_EDGE('',*,*,#1925,.F.);
+#2925=ORIENTED_EDGE('',*,*,#2240,.F.);
+#2926=ORIENTED_EDGE('',*,*,#1935,.T.);
+#2927=ORIENTED_EDGE('',*,*,#1946,.T.);
+#2928=ORIENTED_EDGE('',*,*,#1939,.T.);
+#2929=ORIENTED_EDGE('',*,*,#2241,.T.);
+#2930=ORIENTED_EDGE('',*,*,#1936,.T.);
+#2931=ORIENTED_EDGE('',*,*,#2241,.F.);
+#2932=ORIENTED_EDGE('',*,*,#1938,.T.);
+#2933=ORIENTED_EDGE('',*,*,#2242,.F.);
+#2934=ORIENTED_EDGE('',*,*,#2221,.T.);
+#2935=ORIENTED_EDGE('',*,*,#2204,.T.);
+#2936=ORIENTED_EDGE('',*,*,#2239,.T.);
+#2937=ORIENTED_EDGE('',*,*,#2212,.T.);
+#2938=ORIENTED_EDGE('',*,*,#2229,.T.);
+#2939=ORIENTED_EDGE('',*,*,#2209,.T.);
+#2940=ORIENTED_EDGE('',*,*,#2076,.F.);
+#2941=ORIENTED_EDGE('',*,*,#2243,.T.);
+#2942=ORIENTED_EDGE('',*,*,#2244,.T.);
+#2943=ORIENTED_EDGE('',*,*,#2243,.F.);
+#2944=ORIENTED_EDGE('',*,*,#2244,.F.);
+#2945=ORIENTED_EDGE('',*,*,#2075,.F.);
+#2946=ORIENTED_EDGE('',*,*,#2245,.T.);
+#2947=ORIENTED_EDGE('',*,*,#2246,.T.);
+#2948=ORIENTED_EDGE('',*,*,#2245,.F.);
+#2949=ORIENTED_EDGE('',*,*,#2246,.F.);
+#2950=ORIENTED_EDGE('',*,*,#2074,.F.);
+#2951=ORIENTED_EDGE('',*,*,#2247,.T.);
+#2952=ORIENTED_EDGE('',*,*,#2248,.T.);
+#2953=ORIENTED_EDGE('',*,*,#2247,.F.);
+#2954=ORIENTED_EDGE('',*,*,#2248,.F.);
+#2955=ORIENTED_EDGE('',*,*,#2073,.F.);
+#2956=ORIENTED_EDGE('',*,*,#2249,.T.);
+#2957=ORIENTED_EDGE('',*,*,#2250,.T.);
+#2958=ORIENTED_EDGE('',*,*,#2249,.F.);
+#2959=ORIENTED_EDGE('',*,*,#2250,.F.);
+#2960=ORIENTED_EDGE('',*,*,#2128,.F.);
+#2961=ORIENTED_EDGE('',*,*,#2251,.F.);
+#2962=ORIENTED_EDGE('',*,*,#2252,.F.);
+#2963=ORIENTED_EDGE('',*,*,#2253,.T.);
+#2964=ORIENTED_EDGE('',*,*,#2129,.F.);
+#2965=ORIENTED_EDGE('',*,*,#2253,.F.);
+#2966=ORIENTED_EDGE('',*,*,#2254,.F.);
+#2967=ORIENTED_EDGE('',*,*,#2255,.T.);
+#2968=ORIENTED_EDGE('',*,*,#2126,.F.);
+#2969=ORIENTED_EDGE('',*,*,#2255,.F.);
+#2970=ORIENTED_EDGE('',*,*,#2256,.F.);
+#2971=ORIENTED_EDGE('',*,*,#2257,.T.);
+#2972=ORIENTED_EDGE('',*,*,#2127,.F.);
+#2973=ORIENTED_EDGE('',*,*,#2257,.F.);
+#2974=ORIENTED_EDGE('',*,*,#2258,.F.);
+#2975=ORIENTED_EDGE('',*,*,#2251,.T.);
+#2976=ORIENTED_EDGE('',*,*,#2132,.F.);
+#2977=ORIENTED_EDGE('',*,*,#2259,.F.);
+#2978=ORIENTED_EDGE('',*,*,#2260,.F.);
+#2979=ORIENTED_EDGE('',*,*,#2261,.T.);
+#2980=ORIENTED_EDGE('',*,*,#2133,.F.);
+#2981=ORIENTED_EDGE('',*,*,#2261,.F.);
+#2982=ORIENTED_EDGE('',*,*,#2262,.F.);
+#2983=ORIENTED_EDGE('',*,*,#2263,.T.);
+#2984=ORIENTED_EDGE('',*,*,#2130,.F.);
+#2985=ORIENTED_EDGE('',*,*,#2263,.F.);
+#2986=ORIENTED_EDGE('',*,*,#2264,.F.);
+#2987=ORIENTED_EDGE('',*,*,#2265,.T.);
+#2988=ORIENTED_EDGE('',*,*,#2131,.F.);
+#2989=ORIENTED_EDGE('',*,*,#2265,.F.);
+#2990=ORIENTED_EDGE('',*,*,#2266,.F.);
+#2991=ORIENTED_EDGE('',*,*,#2259,.T.);
+#2992=ORIENTED_EDGE('',*,*,#2136,.F.);
+#2993=ORIENTED_EDGE('',*,*,#2267,.F.);
+#2994=ORIENTED_EDGE('',*,*,#2268,.F.);
+#2995=ORIENTED_EDGE('',*,*,#2269,.T.);
+#2996=ORIENTED_EDGE('',*,*,#2137,.F.);
+#2997=ORIENTED_EDGE('',*,*,#2269,.F.);
+#2998=ORIENTED_EDGE('',*,*,#2270,.F.);
+#2999=ORIENTED_EDGE('',*,*,#2271,.T.);
+#3000=ORIENTED_EDGE('',*,*,#2134,.F.);
+#3001=ORIENTED_EDGE('',*,*,#2271,.F.);
+#3002=ORIENTED_EDGE('',*,*,#2272,.F.);
+#3003=ORIENTED_EDGE('',*,*,#2273,.T.);
+#3004=ORIENTED_EDGE('',*,*,#2135,.F.);
+#3005=ORIENTED_EDGE('',*,*,#2273,.F.);
+#3006=ORIENTED_EDGE('',*,*,#2274,.F.);
+#3007=ORIENTED_EDGE('',*,*,#2267,.T.);
+#3008=ORIENTED_EDGE('',*,*,#2140,.F.);
+#3009=ORIENTED_EDGE('',*,*,#2275,.F.);
+#3010=ORIENTED_EDGE('',*,*,#2276,.F.);
+#3011=ORIENTED_EDGE('',*,*,#2277,.T.);
+#3012=ORIENTED_EDGE('',*,*,#2141,.F.);
+#3013=ORIENTED_EDGE('',*,*,#2277,.F.);
+#3014=ORIENTED_EDGE('',*,*,#2278,.F.);
+#3015=ORIENTED_EDGE('',*,*,#2279,.T.);
+#3016=ORIENTED_EDGE('',*,*,#2138,.F.);
+#3017=ORIENTED_EDGE('',*,*,#2279,.F.);
+#3018=ORIENTED_EDGE('',*,*,#2280,.F.);
+#3019=ORIENTED_EDGE('',*,*,#2281,.T.);
+#3020=ORIENTED_EDGE('',*,*,#2139,.F.);
+#3021=ORIENTED_EDGE('',*,*,#2281,.F.);
+#3022=ORIENTED_EDGE('',*,*,#2282,.F.);
+#3023=ORIENTED_EDGE('',*,*,#2275,.T.);
+#3024=ORIENTED_EDGE('',*,*,#2144,.F.);
+#3025=ORIENTED_EDGE('',*,*,#2283,.F.);
+#3026=ORIENTED_EDGE('',*,*,#2284,.F.);
+#3027=ORIENTED_EDGE('',*,*,#2285,.T.);
+#3028=ORIENTED_EDGE('',*,*,#2145,.F.);
+#3029=ORIENTED_EDGE('',*,*,#2285,.F.);
+#3030=ORIENTED_EDGE('',*,*,#2286,.F.);
+#3031=ORIENTED_EDGE('',*,*,#2287,.T.);
+#3032=ORIENTED_EDGE('',*,*,#2142,.F.);
+#3033=ORIENTED_EDGE('',*,*,#2287,.F.);
+#3034=ORIENTED_EDGE('',*,*,#2288,.F.);
+#3035=ORIENTED_EDGE('',*,*,#2289,.T.);
+#3036=ORIENTED_EDGE('',*,*,#2143,.F.);
+#3037=ORIENTED_EDGE('',*,*,#2289,.F.);
+#3038=ORIENTED_EDGE('',*,*,#2290,.F.);
+#3039=ORIENTED_EDGE('',*,*,#2283,.T.);
+#3040=ORIENTED_EDGE('',*,*,#2291,.F.);
+#3041=ORIENTED_EDGE('',*,*,#2292,.T.);
+#3042=ORIENTED_EDGE('',*,*,#2293,.T.);
+#3043=ORIENTED_EDGE('',*,*,#2294,.F.);
+#3044=ORIENTED_EDGE('',*,*,#2295,.F.);
+#3045=ORIENTED_EDGE('',*,*,#2296,.T.);
+#3046=ORIENTED_EDGE('',*,*,#2297,.T.);
+#3047=ORIENTED_EDGE('',*,*,#2292,.F.);
+#3048=ORIENTED_EDGE('',*,*,#2298,.F.);
+#3049=ORIENTED_EDGE('',*,*,#2299,.T.);
+#3050=ORIENTED_EDGE('',*,*,#2300,.T.);
+#3051=ORIENTED_EDGE('',*,*,#2296,.F.);
+#3052=ORIENTED_EDGE('',*,*,#2301,.F.);
+#3053=ORIENTED_EDGE('',*,*,#2294,.T.);
+#3054=ORIENTED_EDGE('',*,*,#2302,.T.);
+#3055=ORIENTED_EDGE('',*,*,#2299,.F.);
+#3056=ORIENTED_EDGE('',*,*,#2302,.F.);
+#3057=ORIENTED_EDGE('',*,*,#2293,.F.);
+#3058=ORIENTED_EDGE('',*,*,#2297,.F.);
+#3059=ORIENTED_EDGE('',*,*,#2300,.F.);
+#3060=ORIENTED_EDGE('',*,*,#2303,.F.);
+#3061=ORIENTED_EDGE('',*,*,#2304,.T.);
+#3062=ORIENTED_EDGE('',*,*,#2305,.T.);
+#3063=ORIENTED_EDGE('',*,*,#2306,.F.);
+#3064=ORIENTED_EDGE('',*,*,#2307,.F.);
+#3065=ORIENTED_EDGE('',*,*,#2308,.T.);
+#3066=ORIENTED_EDGE('',*,*,#2309,.T.);
+#3067=ORIENTED_EDGE('',*,*,#2304,.F.);
+#3068=ORIENTED_EDGE('',*,*,#2310,.F.);
+#3069=ORIENTED_EDGE('',*,*,#2311,.T.);
+#3070=ORIENTED_EDGE('',*,*,#2312,.T.);
+#3071=ORIENTED_EDGE('',*,*,#2308,.F.);
+#3072=ORIENTED_EDGE('',*,*,#2313,.F.);
+#3073=ORIENTED_EDGE('',*,*,#2306,.T.);
+#3074=ORIENTED_EDGE('',*,*,#2314,.T.);
+#3075=ORIENTED_EDGE('',*,*,#2311,.F.);
+#3076=ORIENTED_EDGE('',*,*,#2314,.F.);
+#3077=ORIENTED_EDGE('',*,*,#2305,.F.);
+#3078=ORIENTED_EDGE('',*,*,#2309,.F.);
+#3079=ORIENTED_EDGE('',*,*,#2312,.F.);
+#3080=ORIENTED_EDGE('',*,*,#2315,.F.);
+#3081=ORIENTED_EDGE('',*,*,#2316,.T.);
+#3082=ORIENTED_EDGE('',*,*,#2317,.T.);
+#3083=ORIENTED_EDGE('',*,*,#2318,.F.);
+#3084=ORIENTED_EDGE('',*,*,#2319,.F.);
+#3085=ORIENTED_EDGE('',*,*,#2320,.T.);
+#3086=ORIENTED_EDGE('',*,*,#2321,.T.);
+#3087=ORIENTED_EDGE('',*,*,#2316,.F.);
+#3088=ORIENTED_EDGE('',*,*,#2322,.F.);
+#3089=ORIENTED_EDGE('',*,*,#2323,.T.);
+#3090=ORIENTED_EDGE('',*,*,#2324,.T.);
+#3091=ORIENTED_EDGE('',*,*,#2320,.F.);
+#3092=ORIENTED_EDGE('',*,*,#2325,.F.);
+#3093=ORIENTED_EDGE('',*,*,#2318,.T.);
+#3094=ORIENTED_EDGE('',*,*,#2326,.T.);
+#3095=ORIENTED_EDGE('',*,*,#2323,.F.);
+#3096=ORIENTED_EDGE('',*,*,#2326,.F.);
+#3097=ORIENTED_EDGE('',*,*,#2317,.F.);
+#3098=ORIENTED_EDGE('',*,*,#2321,.F.);
+#3099=ORIENTED_EDGE('',*,*,#2324,.F.);
+#3100=ORIENTED_EDGE('',*,*,#2327,.F.);
+#3101=ORIENTED_EDGE('',*,*,#2328,.T.);
+#3102=ORIENTED_EDGE('',*,*,#2329,.T.);
+#3103=ORIENTED_EDGE('',*,*,#2330,.F.);
+#3104=ORIENTED_EDGE('',*,*,#2331,.F.);
+#3105=ORIENTED_EDGE('',*,*,#2332,.T.);
+#3106=ORIENTED_EDGE('',*,*,#2333,.T.);
+#3107=ORIENTED_EDGE('',*,*,#2328,.F.);
+#3108=ORIENTED_EDGE('',*,*,#2334,.F.);
+#3109=ORIENTED_EDGE('',*,*,#2335,.T.);
+#3110=ORIENTED_EDGE('',*,*,#2336,.T.);
+#3111=ORIENTED_EDGE('',*,*,#2332,.F.);
+#3112=ORIENTED_EDGE('',*,*,#2337,.F.);
+#3113=ORIENTED_EDGE('',*,*,#2330,.T.);
+#3114=ORIENTED_EDGE('',*,*,#2338,.T.);
+#3115=ORIENTED_EDGE('',*,*,#2335,.F.);
+#3116=ORIENTED_EDGE('',*,*,#2338,.F.);
+#3117=ORIENTED_EDGE('',*,*,#2329,.F.);
+#3118=ORIENTED_EDGE('',*,*,#2333,.F.);
+#3119=ORIENTED_EDGE('',*,*,#2336,.F.);
+#3120=ORIENTED_EDGE('',*,*,#2339,.F.);
+#3121=ORIENTED_EDGE('',*,*,#2340,.T.);
+#3122=ORIENTED_EDGE('',*,*,#2341,.T.);
+#3123=ORIENTED_EDGE('',*,*,#2342,.F.);
+#3124=ORIENTED_EDGE('',*,*,#2343,.F.);
+#3125=ORIENTED_EDGE('',*,*,#2344,.T.);
+#3126=ORIENTED_EDGE('',*,*,#2345,.T.);
+#3127=ORIENTED_EDGE('',*,*,#2340,.F.);
+#3128=ORIENTED_EDGE('',*,*,#2346,.F.);
+#3129=ORIENTED_EDGE('',*,*,#2347,.T.);
+#3130=ORIENTED_EDGE('',*,*,#2348,.T.);
+#3131=ORIENTED_EDGE('',*,*,#2344,.F.);
+#3132=ORIENTED_EDGE('',*,*,#2349,.F.);
+#3133=ORIENTED_EDGE('',*,*,#2342,.T.);
+#3134=ORIENTED_EDGE('',*,*,#2350,.T.);
+#3135=ORIENTED_EDGE('',*,*,#2347,.F.);
+#3136=ORIENTED_EDGE('',*,*,#2350,.F.);
+#3137=ORIENTED_EDGE('',*,*,#2341,.F.);
+#3138=ORIENTED_EDGE('',*,*,#2345,.F.);
+#3139=ORIENTED_EDGE('',*,*,#2348,.F.);
+#3140=ORIENTED_EDGE('',*,*,#2351,.F.);
+#3141=ORIENTED_EDGE('',*,*,#2352,.T.);
+#3142=ORIENTED_EDGE('',*,*,#2353,.F.);
+#3143=ORIENTED_EDGE('',*,*,#2352,.F.);
+#3144=ORIENTED_EDGE('',*,*,#2351,.T.);
+#3145=ORIENTED_EDGE('',*,*,#2354,.F.);
+#3146=ORIENTED_EDGE('',*,*,#2355,.T.);
+#3147=ORIENTED_EDGE('',*,*,#2356,.F.);
+#3148=ORIENTED_EDGE('',*,*,#2355,.F.);
+#3149=ORIENTED_EDGE('',*,*,#2354,.T.);
+#3150=ORIENTED_EDGE('',*,*,#2357,.F.);
+#3151=ORIENTED_EDGE('',*,*,#2358,.T.);
+#3152=ORIENTED_EDGE('',*,*,#2359,.F.);
+#3153=ORIENTED_EDGE('',*,*,#2358,.F.);
+#3154=ORIENTED_EDGE('',*,*,#2357,.T.);
+#3155=ORIENTED_EDGE('',*,*,#2360,.F.);
+#3156=ORIENTED_EDGE('',*,*,#2361,.T.);
+#3157=ORIENTED_EDGE('',*,*,#2362,.F.);
+#3158=ORIENTED_EDGE('',*,*,#2361,.F.);
+#3159=ORIENTED_EDGE('',*,*,#2360,.T.);
+#3160=ORIENTED_EDGE('',*,*,#2363,.F.);
+#3161=ORIENTED_EDGE('',*,*,#2364,.T.);
+#3162=ORIENTED_EDGE('',*,*,#2365,.F.);
+#3163=ORIENTED_EDGE('',*,*,#2364,.F.);
+#3164=ORIENTED_EDGE('',*,*,#2363,.T.);
+#3165=ORIENTED_EDGE('',*,*,#2366,.F.);
+#3166=ORIENTED_EDGE('',*,*,#2036,.F.);
+#3167=ORIENTED_EDGE('',*,*,#2367,.F.);
+#3168=ORIENTED_EDGE('',*,*,#2368,.F.);
+#3169=ORIENTED_EDGE('',*,*,#2199,.F.);
+#3170=ORIENTED_EDGE('',*,*,#2198,.F.);
+#3171=ORIENTED_EDGE('',*,*,#2197,.F.);
+#3172=ORIENTED_EDGE('',*,*,#2066,.F.);
+#3173=ORIENTED_EDGE('',*,*,#2369,.F.);
+#3174=ORIENTED_EDGE('',*,*,#2370,.F.);
+#3175=ORIENTED_EDGE('',*,*,#2371,.F.);
+#3176=ORIENTED_EDGE('',*,*,#2043,.F.);
+#3177=ORIENTED_EDGE('',*,*,#2159,.F.);
+#3178=ORIENTED_EDGE('',*,*,#2372,.F.);
+#3179=ORIENTED_EDGE('',*,*,#2158,.F.);
+#3180=ORIENTED_EDGE('',*,*,#2062,.F.);
+#3181=ORIENTED_EDGE('',*,*,#2160,.F.);
+#3182=ORIENTED_EDGE('',*,*,#2372,.T.);
+#3183=ORIENTED_EDGE('',*,*,#2373,.F.);
+#3184=ORIENTED_EDGE('',*,*,#2374,.F.);
+#3185=ORIENTED_EDGE('',*,*,#2375,.F.);
+#3186=ORIENTED_EDGE('',*,*,#2039,.F.);
+#3187=ORIENTED_EDGE('',*,*,#2376,.F.);
+#3188=ORIENTED_EDGE('',*,*,#2056,.F.);
+#3189=ORIENTED_EDGE('',*,*,#2377,.F.);
+#3190=ORIENTED_EDGE('',*,*,#2378,.F.);
+#3191=ORIENTED_EDGE('',*,*,#2379,.F.);
+#3192=ORIENTED_EDGE('',*,*,#2380,.F.);
+#3193=ORIENTED_EDGE('',*,*,#2381,.F.);
+#3194=ORIENTED_EDGE('',*,*,#2046,.F.);
+#3195=ORIENTED_EDGE('',*,*,#2366,.T.);
+#3196=ORIENTED_EDGE('',*,*,#2382,.F.);
+#3197=ORIENTED_EDGE('',*,*,#2383,.T.);
+#3198=ORIENTED_EDGE('',*,*,#2037,.F.);
+#3199=ORIENTED_EDGE('',*,*,#2371,.T.);
+#3200=ORIENTED_EDGE('',*,*,#2384,.F.);
+#3201=ORIENTED_EDGE('',*,*,#2385,.T.);
+#3202=ORIENTED_EDGE('',*,*,#2044,.F.);
+#3203=ORIENTED_EDGE('',*,*,#2369,.T.);
+#3204=ORIENTED_EDGE('',*,*,#2042,.F.);
+#3205=ORIENTED_EDGE('',*,*,#2386,.F.);
+#3206=ORIENTED_EDGE('',*,*,#2387,.F.);
+#3207=ORIENTED_EDGE('',*,*,#2188,.F.);
+#3208=ORIENTED_EDGE('',*,*,#2388,.T.);
+#3209=ORIENTED_EDGE('',*,*,#2059,.F.);
+#3210=ORIENTED_EDGE('',*,*,#2389,.F.);
+#3211=ORIENTED_EDGE('',*,*,#2375,.T.);
+#3212=ORIENTED_EDGE('',*,*,#2390,.F.);
+#3213=ORIENTED_EDGE('',*,*,#2391,.T.);
+#3214=ORIENTED_EDGE('',*,*,#2040,.F.);
+#3215=ORIENTED_EDGE('',*,*,#2373,.T.);
+#3216=ORIENTED_EDGE('',*,*,#2038,.F.);
+#3217=ORIENTED_EDGE('',*,*,#2383,.F.);
+#3218=ORIENTED_EDGE('',*,*,#2392,.F.);
+#3219=ORIENTED_EDGE('',*,*,#2368,.T.);
+#3220=ORIENTED_EDGE('',*,*,#2393,.T.);
+#3221=ORIENTED_EDGE('',*,*,#2394,.T.);
+#3222=ORIENTED_EDGE('',*,*,#2395,.T.);
+#3223=ORIENTED_EDGE('',*,*,#2396,.T.);
+#3224=ORIENTED_EDGE('',*,*,#2397,.T.);
+#3225=ORIENTED_EDGE('',*,*,#2380,.T.);
+#3226=ORIENTED_EDGE('',*,*,#2398,.T.);
+#3227=ORIENTED_EDGE('',*,*,#2384,.T.);
+#3228=ORIENTED_EDGE('',*,*,#2370,.T.);
+#3229=ORIENTED_EDGE('',*,*,#2387,.T.);
+#3230=ORIENTED_EDGE('',*,*,#2399,.T.);
+#3231=ORIENTED_EDGE('',*,*,#2390,.T.);
+#3232=ORIENTED_EDGE('',*,*,#2374,.T.);
+#3233=ORIENTED_EDGE('',*,*,#2392,.T.);
+#3234=ORIENTED_EDGE('',*,*,#2382,.T.);
+#3235=ORIENTED_EDGE('',*,*,#2242,.T.);
+#3236=ORIENTED_EDGE('',*,*,#1937,.T.);
+#3237=ORIENTED_EDGE('',*,*,#1947,.T.);
+#3238=ORIENTED_EDGE('',*,*,#1957,.T.);
+#3239=ORIENTED_EDGE('',*,*,#1954,.T.);
+#3240=ORIENTED_EDGE('',*,*,#1951,.T.);
+#3241=ORIENTED_EDGE('',*,*,#1959,.T.);
+#3242=ORIENTED_EDGE('',*,*,#1969,.T.);
+#3243=ORIENTED_EDGE('',*,*,#1966,.T.);
+#3244=ORIENTED_EDGE('',*,*,#1963,.T.);
+#3245=ORIENTED_EDGE('',*,*,#1971,.T.);
+#3246=ORIENTED_EDGE('',*,*,#1981,.T.);
+#3247=ORIENTED_EDGE('',*,*,#1978,.T.);
+#3248=ORIENTED_EDGE('',*,*,#1975,.T.);
+#3249=ORIENTED_EDGE('',*,*,#1983,.T.);
+#3250=ORIENTED_EDGE('',*,*,#1993,.T.);
+#3251=ORIENTED_EDGE('',*,*,#1990,.T.);
+#3252=ORIENTED_EDGE('',*,*,#1987,.T.);
+#3253=ORIENTED_EDGE('',*,*,#1995,.T.);
+#3254=ORIENTED_EDGE('',*,*,#2005,.T.);
+#3255=ORIENTED_EDGE('',*,*,#2002,.T.);
+#3256=ORIENTED_EDGE('',*,*,#1999,.T.);
+#3257=ORIENTED_EDGE('',*,*,#2219,.T.);
+#3258=ORIENTED_EDGE('',*,*,#2238,.T.);
+#3259=ORIENTED_EDGE('',*,*,#2228,.T.);
+#3260=ORIENTED_EDGE('',*,*,#2256,.T.);
+#3261=ORIENTED_EDGE('',*,*,#2254,.T.);
+#3262=ORIENTED_EDGE('',*,*,#2252,.T.);
+#3263=ORIENTED_EDGE('',*,*,#2258,.T.);
+#3264=ORIENTED_EDGE('',*,*,#2264,.T.);
+#3265=ORIENTED_EDGE('',*,*,#2262,.T.);
+#3266=ORIENTED_EDGE('',*,*,#2260,.T.);
+#3267=ORIENTED_EDGE('',*,*,#2266,.T.);
+#3268=ORIENTED_EDGE('',*,*,#2272,.T.);
+#3269=ORIENTED_EDGE('',*,*,#2270,.T.);
+#3270=ORIENTED_EDGE('',*,*,#2268,.T.);
+#3271=ORIENTED_EDGE('',*,*,#2274,.T.);
+#3272=ORIENTED_EDGE('',*,*,#2280,.T.);
+#3273=ORIENTED_EDGE('',*,*,#2278,.T.);
+#3274=ORIENTED_EDGE('',*,*,#2276,.T.);
+#3275=ORIENTED_EDGE('',*,*,#2282,.T.);
+#3276=ORIENTED_EDGE('',*,*,#2288,.T.);
+#3277=ORIENTED_EDGE('',*,*,#2286,.T.);
+#3278=ORIENTED_EDGE('',*,*,#2284,.T.);
+#3279=ORIENTED_EDGE('',*,*,#2290,.T.);
+#3280=ORIENTED_EDGE('',*,*,#2291,.T.);
+#3281=ORIENTED_EDGE('',*,*,#2301,.T.);
+#3282=ORIENTED_EDGE('',*,*,#2298,.T.);
+#3283=ORIENTED_EDGE('',*,*,#2295,.T.);
+#3284=ORIENTED_EDGE('',*,*,#2303,.T.);
+#3285=ORIENTED_EDGE('',*,*,#2313,.T.);
+#3286=ORIENTED_EDGE('',*,*,#2310,.T.);
+#3287=ORIENTED_EDGE('',*,*,#2307,.T.);
+#3288=ORIENTED_EDGE('',*,*,#2315,.T.);
+#3289=ORIENTED_EDGE('',*,*,#2325,.T.);
+#3290=ORIENTED_EDGE('',*,*,#2322,.T.);
+#3291=ORIENTED_EDGE('',*,*,#2319,.T.);
+#3292=ORIENTED_EDGE('',*,*,#2327,.T.);
+#3293=ORIENTED_EDGE('',*,*,#2337,.T.);
+#3294=ORIENTED_EDGE('',*,*,#2334,.T.);
+#3295=ORIENTED_EDGE('',*,*,#2331,.T.);
+#3296=ORIENTED_EDGE('',*,*,#2339,.T.);
+#3297=ORIENTED_EDGE('',*,*,#2349,.T.);
+#3298=ORIENTED_EDGE('',*,*,#2346,.T.);
+#3299=ORIENTED_EDGE('',*,*,#2343,.T.);
+#3300=ORIENTED_EDGE('',*,*,#2353,.T.);
+#3301=ORIENTED_EDGE('',*,*,#2356,.T.);
+#3302=ORIENTED_EDGE('',*,*,#2359,.T.);
+#3303=ORIENTED_EDGE('',*,*,#2362,.T.);
+#3304=ORIENTED_EDGE('',*,*,#2365,.T.);
+#3305=ORIENTED_EDGE('',*,*,#2379,.T.);
+#3306=ORIENTED_EDGE('',*,*,#2045,.F.);
+#3307=ORIENTED_EDGE('',*,*,#2385,.F.);
+#3308=ORIENTED_EDGE('',*,*,#2398,.F.);
+#3309=ORIENTED_EDGE('',*,*,#2025,.T.);
+#3310=ORIENTED_EDGE('',*,*,#2080,.T.);
+#3311=ORIENTED_EDGE('',*,*,#2029,.T.);
+#3312=ORIENTED_EDGE('',*,*,#2400,.T.);
+#3313=ORIENTED_EDGE('',*,*,#2184,.F.);
+#3314=ORIENTED_EDGE('',*,*,#2401,.T.);
+#3315=ORIENTED_EDGE('',*,*,#2057,.F.);
+#3316=ORIENTED_EDGE('',*,*,#2376,.T.);
+#3317=ORIENTED_EDGE('',*,*,#2378,.T.);
+#3318=ORIENTED_EDGE('',*,*,#2377,.T.);
+#3319=ORIENTED_EDGE('',*,*,#2055,.F.);
+#3320=ORIENTED_EDGE('',*,*,#2402,.F.);
+#3321=ORIENTED_EDGE('',*,*,#2399,.F.);
+#3322=ORIENTED_EDGE('',*,*,#2386,.T.);
+#3323=ORIENTED_EDGE('',*,*,#2041,.F.);
+#3324=ORIENTED_EDGE('',*,*,#2391,.F.);
+#3325=ORIENTED_EDGE('',*,*,#2381,.T.);
+#3326=ORIENTED_EDGE('',*,*,#2397,.F.);
+#3327=ORIENTED_EDGE('',*,*,#2403,.T.);
+#3328=ORIENTED_EDGE('',*,*,#2047,.F.);
+#3329=ORIENTED_EDGE('',*,*,#2396,.F.);
+#3330=ORIENTED_EDGE('',*,*,#2404,.T.);
+#3331=ORIENTED_EDGE('',*,*,#2048,.F.);
+#3332=ORIENTED_EDGE('',*,*,#2403,.F.);
+#3333=ORIENTED_EDGE('',*,*,#2026,.T.);
+#3334=ORIENTED_EDGE('',*,*,#2400,.F.);
+#3335=ORIENTED_EDGE('',*,*,#2032,.T.);
+#3336=ORIENTED_EDGE('',*,*,#2049,.F.);
+#3337=ORIENTED_EDGE('',*,*,#2404,.F.);
+#3338=ORIENTED_EDGE('',*,*,#2395,.F.);
+#3339=ORIENTED_EDGE('',*,*,#2405,.T.);
+#3340=ORIENTED_EDGE('',*,*,#2033,.F.);
+#3341=ORIENTED_EDGE('',*,*,#2394,.F.);
+#3342=ORIENTED_EDGE('',*,*,#2406,.T.);
+#3343=ORIENTED_EDGE('',*,*,#2034,.F.);
+#3344=ORIENTED_EDGE('',*,*,#2405,.F.);
+#3345=ORIENTED_EDGE('',*,*,#2367,.T.);
+#3346=ORIENTED_EDGE('',*,*,#2035,.F.);
+#3347=ORIENTED_EDGE('',*,*,#2406,.F.);
+#3348=ORIENTED_EDGE('',*,*,#2393,.F.);
+#3349=ORIENTED_EDGE('',*,*,#2146,.F.);
+#3350=ORIENTED_EDGE('',*,*,#2166,.F.);
+#3351=ORIENTED_EDGE('',*,*,#2200,.T.);
+#3352=ORIENTED_EDGE('',*,*,#2064,.F.);
+#3353=ORIENTED_EDGE('',*,*,#2157,.F.);
+#3354=ORIENTED_EDGE('',*,*,#2202,.T.);
+#3355=ORIENTED_EDGE('',*,*,#2189,.F.);
+#3356=ORIENTED_EDGE('',*,*,#2161,.T.);
+#3357=ORIENTED_EDGE('',*,*,#2060,.F.);
+#3358=ORIENTED_EDGE('',*,*,#2388,.F.);
+#3359=ORIENTED_EDGE('',*,*,#2186,.F.);
+#3360=ORIENTED_EDGE('',*,*,#2389,.T.);
+#3361=ORIENTED_EDGE('',*,*,#2058,.F.);
+#3362=ORIENTED_EDGE('',*,*,#2401,.F.);
+#3363=ORIENTED_EDGE('',*,*,#2182,.F.);
+#3364=ORIENTED_EDGE('',*,*,#2402,.T.);
+#3365=ORIENTED_EDGE('',*,*,#2054,.F.);
+#3366=ORIENTED_EDGE('',*,*,#2191,.F.);
+#3367=ORIENTED_EDGE('',*,*,#2190,.F.);
+#3368=ORIENTED_EDGE('',*,*,#2052,.F.);
+#3369=ORIENTED_EDGE('',*,*,#2192,.F.);
+#3370=ORIENTED_EDGE('',*,*,#2180,.F.);
+#3371=ORIENTED_EDGE('',*,*,#2193,.F.);
+#3372=ORIENTED_EDGE('',*,*,#2070,.F.);
+#3373=ORIENTED_EDGE('',*,*,#2195,.F.);
+#3374=ORIENTED_EDGE('',*,*,#2173,.F.);
+#3375=B_SPLINE_SURFACE_WITH_KNOTS('',3,3,((#4991,#4992,#4993,#4994),(#4995,
+#4996,#4997,#4998),(#4999,#5000,#5001,#5002),(#5003,#5004,#5005,#5006)),
+ .UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(0.310984873946817,1.),(-0.0524068809145321,
+5.55111512312578E-16),.UNSPECIFIED.);
+#3376=B_SPLINE_SURFACE_WITH_KNOTS('',3,3,((#5029,#5030,#5031,#5032,#5033,
+#5034,#5035,#5036,#5037,#5038,#5039,#5040,#5041,#5042,#5043),(#5044,#5045,
+#5046,#5047,#5048,#5049,#5050,#5051,#5052,#5053,#5054,#5055,#5056,#5057,
+#5058),(#5059,#5060,#5061,#5062,#5063,#5064,#5065,#5066,#5067,#5068,#5069,
+#5070,#5071,#5072,#5073),(#5074,#5075,#5076,#5077,#5078,#5079,#5080,#5081,
+#5082,#5083,#5084,#5085,#5086,#5087,#5088)),.UNSPECIFIED.,.F.,.F.,.F.,(4,
+4),(4,1,1,1,1,1,1,1,1,1,1,1,4),(0.299580335663529,1.),(-0.471439789921594,
+-0.404091248504223,-0.370416977795537,-0.336742707086852,-0.291843679475271,
+-0.280618922572376,-0.269394165669481,-0.2244951380579,-0.20204562425211,
+-0.168371353543424,-0.134697082834739,-0.0673485414173676,3.44169137633799E-15),
+ .UNSPECIFIED.);
+#3377=B_SPLINE_SURFACE_WITH_KNOTS('',3,3,((#5738,#5739,#5740,#5741,#5742,
+#5743,#5744,#5745,#5746,#5747,#5748,#5749,#5750,#5751,#5752,#5753,#5754,
+#5755,#5756,#5757,#5758,#5759,#5760,#5761,#5762,#5763,#5764),(#5765,#5766,
+#5767,#5768,#5769,#5770,#5771,#5772,#5773,#5774,#5775,#5776,#5777,#5778,
+#5779,#5780,#5781,#5782,#5783,#5784,#5785,#5786,#5787,#5788,#5789,#5790,
+#5791),(#5792,#5793,#5794,#5795,#5796,#5797,#5798,#5799,#5800,#5801,#5802,
+#5803,#5804,#5805,#5806,#5807,#5808,#5809,#5810,#5811,#5812,#5813,#5814,
+#5815,#5816,#5817,#5818),(#5819,#5820,#5821,#5822,#5823,#5824,#5825,#5826,
+#5827,#5828,#5829,#5830,#5831,#5832,#5833,#5834,#5835,#5836,#5837,#5838,
+#5839,#5840,#5841,#5842,#5843,#5844,#5845),(#5846,#5847,#5848,#5849,#5850,
+#5851,#5852,#5853,#5854,#5855,#5856,#5857,#5858,#5859,#5860,#5861,#5862,
+#5863,#5864,#5865,#5866,#5867,#5868,#5869,#5870,#5871,#5872)),
+ .UNSPECIFIED.,.F.,.F.,.F.,(4,1,4),(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,
+1,1,1,1,1,1,4),(0.,0.571428571428571,1.),(0.,0.0207747927006334,0.0415495854012669,
+0.0830991708025337,0.124648756203801,0.186973134305701,0.249297512407601,
+0.290847097808868,0.311621890509501,0.322009286859818,0.332396683210135,
+0.360096406810979,0.415495854012669,0.498595024815202,0.519369817515836,
+0.540144610216469,0.550532006566786,0.560919402917103,0.571306799267419,
+0.573903648354999,0.576500497442578,0.579097346530157,0.580395771073946,
+0.581044983345841,0.581694195617736),.UNSPECIFIED.);
+#3378=B_SPLINE_SURFACE_WITH_KNOTS('',3,3,((#5950,#5951,#5952,#5953,#5954,
+#5955,#5956,#5957,#5958,#5959,#5960,#5961,#5962,#5963,#5964,#5965,#5966,
+#5967,#5968),(#5969,#5970,#5971,#5972,#5973,#5974,#5975,#5976,#5977,#5978,
+#5979,#5980,#5981,#5982,#5983,#5984,#5985,#5986,#5987),(#5988,#5989,#5990,
+#5991,#5992,#5993,#5994,#5995,#5996,#5997,#5998,#5999,#6000,#6001,#6002,
+#6003,#6004,#6005,#6006),(#6007,#6008,#6009,#6010,#6011,#6012,#6013,#6014,
+#6015,#6016,#6017,#6018,#6019,#6020,#6021,#6022,#6023,#6024,#6025),(#6026,
+#6027,#6028,#6029,#6030,#6031,#6032,#6033,#6034,#6035,#6036,#6037,#6038,
+#6039,#6040,#6041,#6042,#6043,#6044)),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,4),
+(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.,0.571428571428571,1.),(6.65191408180362E-12,
+0.0207798681036635,0.041559736200675,0.0831194723946981,0.166238944782744,
+0.332477889558837,0.37403762575286,0.457157098140906,0.498716834334929,
+0.519496702431941,0.529886636480446,0.540276570528952,0.550666504577458,
+0.561056438625964,0.57144637267447,0.576641339698722,0.581836306722975),
+ .UNSPECIFIED.);
+#3379=B_SPLINE_SURFACE_WITH_KNOTS('',3,3,((#6234,#6235,#6236,#6237,#6238,
+#6239),(#6240,#6241,#6242,#6243,#6244,#6245),(#6246,#6247,#6248,#6249,#6250,
+#6251),(#6252,#6253,#6254,#6255,#6256,#6257),(#6258,#6259,#6260,#6261,#6262,
+#6263)),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,4),(4,1,1,4),(0.,0.571428571428571,
+1.),(2.54983890347792,2.73023275458932,2.91062660570071,3.18121738236781),
+ .UNSPECIFIED.);
+#3380=B_SPLINE_SURFACE_WITH_KNOTS('',3,3,((#6394,#6395,#6396,#6397,#6398,
+#6399,#6400,#6401,#6402,#6403),(#6404,#6405,#6406,#6407,#6408,#6409,#6410,
+#6411,#6412,#6413),(#6414,#6415,#6416,#6417,#6418,#6419,#6420,#6421,#6422,
+#6423),(#6424,#6425,#6426,#6427,#6428,#6429,#6430,#6431,#6432,#6433)),
+ .UNSPECIFIED.,.F.,.T.,.F.,(4,4),(4,1,1,1,1,1,1,4),(0.,1.),(-3.14149314110212,
+-2.24389524007646,-1.34629733905081,-0.448699438025151,0.448898463000504,
+1.34649636402616,2.24409426505181,3.14169216607747),.UNSPECIFIED.);
+#3381=B_SPLINE_SURFACE_WITH_KNOTS('',3,3,((#6450,#6451,#6452,#6453),(#6454,
+#6455,#6456,#6457),(#6458,#6459,#6460,#6461),(#6462,#6463,#6464,#6465)),
+ .UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(0.301969092933824,1.),(-0.471448308997152,
+-0.47143978992159),.UNSPECIFIED.);
+#3382=B_SPLINE_SURFACE_WITH_KNOTS('',3,3,((#6518,#6519,#6520,#6521,#6522,
+#6523,#6524,#6525,#6526,#6527,#6528),(#6529,#6530,#6531,#6532,#6533,#6534,
+#6535,#6536,#6537,#6538,#6539),(#6540,#6541,#6542,#6543,#6544,#6545,#6546,
+#6547,#6548,#6549,#6550),(#6551,#6552,#6553,#6554,#6555,#6556,#6557,#6558,
+#6559,#6560,#6561)),.UNSPECIFIED.,.F.,.T.,.F.,(4,4),(4,1,1,1,1,1,1,1,4),
+(0.,1.),(-3.80778963256358,-2.91019173153792,-2.01259383051227,-1.11499592948661,
+-0.217398028460956,0.680199872564699,0.904599347821113,1.57779777359035,
+2.47539567461601),.UNSPECIFIED.);
+#3383=B_SPLINE_SURFACE_WITH_KNOTS('',3,3,((#6610,#6611,#6612,#6613,#6614,
+#6615,#6616,#6617,#6618,#6619,#6620,#6621,#6622,#6623,#6624,#6625,#6626,
+#6627,#6628,#6629),(#6630,#6631,#6632,#6633,#6634,#6635,#6636,#6637,#6638,
+#6639,#6640,#6641,#6642,#6643,#6644,#6645,#6646,#6647,#6648,#6649),(#6650,
+#6651,#6652,#6653,#6654,#6655,#6656,#6657,#6658,#6659,#6660,#6661,#6662,
+#6663,#6664,#6665,#6666,#6667,#6668,#6669),(#6670,#6671,#6672,#6673,#6674,
+#6675,#6676,#6677,#6678,#6679,#6680,#6681,#6682,#6683,#6684,#6685,#6686,
+#6687,#6688,#6689)),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,1,1,1,1,1,1,1,1,
+1,1,1,1,1,1,1,1,4),(0.297153349413409,1.),(-0.494679413076073,-0.463088517920955,
+-0.431497622765837,-0.399906727610719,-0.392009003821939,-0.368315832455601,
+-0.363050683263081,-0.357785534070562,-0.347255235685522,-0.326194638915444,
+-0.305134042145365,-0.241952251835129,-0.178770461524893,-0.170872737736114,
+-0.162975013947334,-0.147179566369776,-0.115588671214658,-0.0524068809044219),
+ .UNSPECIFIED.);
+#3384=ADVANCED_FACE('',(#968),#3375,.F.);
+#3385=ADVANCED_FACE('',(#969),#3376,.F.);
+#3386=ADVANCED_FACE('',(#970),#860,.F.);
+#3387=ADVANCED_FACE('',(#971,#221),#861,.T.);
+#3388=ADVANCED_FACE('',(#972),#158,.T.);
+#3389=ADVANCED_FACE('',(#973),#156,.T.);
+#3390=ADVANCED_FACE('',(#974),#862,.F.);
+#3391=ADVANCED_FACE('',(#975),#863,.F.);
+#3392=ADVANCED_FACE('',(#976),#864,.F.);
+#3393=ADVANCED_FACE('',(#977),#865,.F.);
+#3394=ADVANCED_FACE('',(#978),#866,.F.);
+#3395=ADVANCED_FACE('',(#979),#867,.F.);
+#3396=ADVANCED_FACE('',(#980),#868,.F.);
+#3397=ADVANCED_FACE('',(#981),#869,.F.);
+#3398=ADVANCED_FACE('',(#982),#870,.F.);
+#3399=ADVANCED_FACE('',(#983),#871,.F.);
+#3400=ADVANCED_FACE('',(#984),#872,.F.);
+#3401=ADVANCED_FACE('',(#985),#873,.F.);
+#3402=ADVANCED_FACE('',(#986),#874,.F.);
+#3403=ADVANCED_FACE('',(#987),#875,.F.);
+#3404=ADVANCED_FACE('',(#988),#876,.F.);
+#3405=ADVANCED_FACE('',(#989),#877,.F.);
+#3406=ADVANCED_FACE('',(#990),#878,.F.);
+#3407=ADVANCED_FACE('',(#991),#879,.F.);
+#3408=ADVANCED_FACE('',(#992),#880,.F.);
+#3409=ADVANCED_FACE('',(#993),#881,.F.);
+#3410=ADVANCED_FACE('',(#994),#882,.F.);
+#3411=ADVANCED_FACE('',(#995),#883,.F.);
+#3412=ADVANCED_FACE('',(#996),#884,.F.);
+#3413=ADVANCED_FACE('',(#997),#885,.F.);
+#3414=ADVANCED_FACE('',(#998),#886,.F.);
+#3415=ADVANCED_FACE('',(#999),#159,.F.);
+#3416=ADVANCED_FACE('',(#1000),#160,.F.);
+#3417=ADVANCED_FACE('',(#1001),#887,.T.);
+#3418=ADVANCED_FACE('',(#1002),#161,.F.);
+#3419=ADVANCED_FACE('',(#1003),#162,.F.);
+#3420=ADVANCED_FACE('',(#1004,#222,#223,#224,#225),#888,.T.);
+#3421=ADVANCED_FACE('',(#1005),#889,.T.);
+#3422=ADVANCED_FACE('',(#1006),#152,.T.);
+#3423=ADVANCED_FACE('',(#1007),#163,.T.);
+#3424=ADVANCED_FACE('',(#1008),#3377,.F.);
+#3425=ADVANCED_FACE('',(#1009),#164,.T.);
+#3426=ADVANCED_FACE('',(#1010),#153,.T.);
+#3427=ADVANCED_FACE('',(#1011),#165,.T.);
+#3428=ADVANCED_FACE('',(#1012),#3378,.F.);
+#3429=ADVANCED_FACE('',(#1013),#166,.T.);
+#3430=ADVANCED_FACE('',(#1014),#167,.T.);
+#3431=ADVANCED_FACE('',(#1015),#890,.T.);
+#3432=ADVANCED_FACE('',(#1016),#140,.F.);
+#3433=ADVANCED_FACE('',(#1017,#226,#227,#228,#229,#230),#891,.F.);
+#3434=ADVANCED_FACE('',(#1018),#168,.F.);
+#3435=ADVANCED_FACE('',(#1019),#169,.F.);
+#3436=ADVANCED_FACE('',(#1020),#170,.F.);
+#3437=ADVANCED_FACE('',(#1021),#3379,.T.);
+#3438=ADVANCED_FACE('',(#1022),#141,.T.);
+#3439=ADVANCED_FACE('',(#1023),#171,.T.);
+#3440=ADVANCED_FACE('',(#1024),#142,.T.);
+#3441=ADVANCED_FACE('',(#1025),#172,.T.);
+#3442=ADVANCED_FACE('',(#1026),#143,.T.);
+#3443=ADVANCED_FACE('',(#1027),#144,.T.);
+#3444=ADVANCED_FACE('',(#1028),#154,.T.);
+#3445=ADVANCED_FACE('',(#1029),#173,.T.);
+#3446=ADVANCED_FACE('',(#1030),#155,.T.);
+#3447=ADVANCED_FACE('',(#1031),#174,.T.);
+#3448=ADVANCED_FACE('',(#1032),#145,.T.);
+#3449=ADVANCED_FACE('',(#1033),#175,.T.);
+#3450=ADVANCED_FACE('',(#1034),#146,.T.);
+#3451=ADVANCED_FACE('',(#1035),#147,.T.);
+#3452=ADVANCED_FACE('',(#1036),#176,.T.);
+#3453=ADVANCED_FACE('',(#1037),#148,.T.);
+#3454=ADVANCED_FACE('',(#1038),#149,.T.);
+#3455=ADVANCED_FACE('',(#1039),#177,.F.);
+#3456=ADVANCED_FACE('',(#1040),#178,.T.);
+#3457=ADVANCED_FACE('',(#1041),#179,.T.);
+#3458=ADVANCED_FACE('',(#1042),#180,.F.);
+#3459=ADVANCED_FACE('',(#1043),#181,.T.);
+#3460=ADVANCED_FACE('',(#1044),#182,.T.);
+#3461=ADVANCED_FACE('',(#1045),#892,.T.);
+#3462=ADVANCED_FACE('',(#1046,#231,#232),#893,.T.);
+#3463=ADVANCED_FACE('',(#1047),#894,.T.);
+#3464=ADVANCED_FACE('',(#1048),#183,.F.);
+#3465=ADVANCED_FACE('',(#1049),#895,.T.);
+#3466=ADVANCED_FACE('',(#1050),#184,.F.);
+#3467=ADVANCED_FACE('',(#1051),#896,.T.);
+#3468=ADVANCED_FACE('',(#1052),#185,.F.);
+#3469=ADVANCED_FACE('',(#1053),#897,.T.);
+#3470=ADVANCED_FACE('',(#1054),#186,.F.);
+#3471=ADVANCED_FACE('',(#1055),#898,.T.);
+#3472=ADVANCED_FACE('',(#1056),#3380,.T.);
+#3473=ADVANCED_FACE('',(#1057),#3381,.F.);
+#3474=ADVANCED_FACE('',(#1058),#187,.T.);
+#3475=ADVANCED_FACE('',(#1059),#188,.T.);
+#3476=ADVANCED_FACE('',(#1060),#150,.F.);
+#3477=ADVANCED_FACE('',(#1061),#157,.T.);
+#3478=ADVANCED_FACE('',(#1062),#189,.T.);
+#3479=ADVANCED_FACE('',(#1063),#190,.T.);
+#3480=ADVANCED_FACE('',(#1064),#3382,.T.);
+#3481=ADVANCED_FACE('',(#1065),#3383,.F.);
+#3482=ADVANCED_FACE('',(#1066),#191,.T.);
+#3483=ADVANCED_FACE('',(#1067),#192,.T.);
+#3484=ADVANCED_FACE('',(#1068),#151,.F.);
+#3485=ADVANCED_FACE('',(#1069),#193,.T.);
+#3486=ADVANCED_FACE('',(#1070,#233),#899,.T.);
+#3487=ADVANCED_FACE('',(#1071,#234),#900,.T.);
+#3488=ADVANCED_FACE('',(#1072,#235),#901,.T.);
+#3489=ADVANCED_FACE('',(#1073),#194,.F.);
+#3490=ADVANCED_FACE('',(#1074),#902,.T.);
+#3491=ADVANCED_FACE('',(#1075),#195,.F.);
+#3492=ADVANCED_FACE('',(#1076),#903,.T.);
+#3493=ADVANCED_FACE('',(#1077),#196,.F.);
+#3494=ADVANCED_FACE('',(#1078),#904,.T.);
+#3495=ADVANCED_FACE('',(#1079),#197,.F.);
+#3496=ADVANCED_FACE('',(#1080),#905,.T.);
+#3497=ADVANCED_FACE('',(#1081),#906,.F.);
+#3498=ADVANCED_FACE('',(#1082),#907,.F.);
+#3499=ADVANCED_FACE('',(#1083),#908,.F.);
+#3500=ADVANCED_FACE('',(#1084),#909,.F.);
+#3501=ADVANCED_FACE('',(#1085),#910,.F.);
+#3502=ADVANCED_FACE('',(#1086),#911,.F.);
+#3503=ADVANCED_FACE('',(#1087),#912,.F.);
+#3504=ADVANCED_FACE('',(#1088),#913,.F.);
+#3505=ADVANCED_FACE('',(#1089),#914,.F.);
+#3506=ADVANCED_FACE('',(#1090),#915,.F.);
+#3507=ADVANCED_FACE('',(#1091),#916,.F.);
+#3508=ADVANCED_FACE('',(#1092),#917,.F.);
+#3509=ADVANCED_FACE('',(#1093),#918,.F.);
+#3510=ADVANCED_FACE('',(#1094),#919,.F.);
+#3511=ADVANCED_FACE('',(#1095),#920,.F.);
+#3512=ADVANCED_FACE('',(#1096),#921,.F.);
+#3513=ADVANCED_FACE('',(#1097),#922,.F.);
+#3514=ADVANCED_FACE('',(#1098),#923,.F.);
+#3515=ADVANCED_FACE('',(#1099),#924,.F.);
+#3516=ADVANCED_FACE('',(#1100),#925,.F.);
+#3517=ADVANCED_FACE('',(#1101),#926,.F.);
+#3518=ADVANCED_FACE('',(#1102),#927,.F.);
+#3519=ADVANCED_FACE('',(#1103),#928,.F.);
+#3520=ADVANCED_FACE('',(#1104),#929,.F.);
+#3521=ADVANCED_FACE('',(#1105),#930,.F.);
+#3522=ADVANCED_FACE('',(#1106),#931,.F.);
+#3523=ADVANCED_FACE('',(#1107),#932,.F.);
+#3524=ADVANCED_FACE('',(#1108),#933,.F.);
+#3525=ADVANCED_FACE('',(#1109),#934,.F.);
+#3526=ADVANCED_FACE('',(#1110),#935,.F.);
+#3527=ADVANCED_FACE('',(#1111),#936,.F.);
+#3528=ADVANCED_FACE('',(#1112),#937,.F.);
+#3529=ADVANCED_FACE('',(#1113),#938,.F.);
+#3530=ADVANCED_FACE('',(#1114),#939,.F.);
+#3531=ADVANCED_FACE('',(#1115),#940,.F.);
+#3532=ADVANCED_FACE('',(#1116),#941,.F.);
+#3533=ADVANCED_FACE('',(#1117),#942,.F.);
+#3534=ADVANCED_FACE('',(#1118),#943,.F.);
+#3535=ADVANCED_FACE('',(#1119),#944,.F.);
+#3536=ADVANCED_FACE('',(#1120),#945,.F.);
+#3537=ADVANCED_FACE('',(#1121),#946,.F.);
+#3538=ADVANCED_FACE('',(#1122),#947,.F.);
+#3539=ADVANCED_FACE('',(#1123),#948,.F.);
+#3540=ADVANCED_FACE('',(#1124),#949,.F.);
+#3541=ADVANCED_FACE('',(#1125),#950,.F.);
+#3542=ADVANCED_FACE('',(#1126),#198,.T.);
+#3543=ADVANCED_FACE('',(#1127),#951,.T.);
+#3544=ADVANCED_FACE('',(#1128),#199,.T.);
+#3545=ADVANCED_FACE('',(#1129),#952,.T.);
+#3546=ADVANCED_FACE('',(#1130),#200,.T.);
+#3547=ADVANCED_FACE('',(#1131),#953,.T.);
+#3548=ADVANCED_FACE('',(#1132),#201,.T.);
+#3549=ADVANCED_FACE('',(#1133),#954,.T.);
+#3550=ADVANCED_FACE('',(#1134),#202,.T.);
+#3551=ADVANCED_FACE('',(#1135),#955,.T.);
+#3552=ADVANCED_FACE('',(#1136),#203,.T.);
+#3553=ADVANCED_FACE('',(#1137),#204,.T.);
+#3554=ADVANCED_FACE('',(#1138),#205,.T.);
+#3555=ADVANCED_FACE('',(#1139),#956,.F.);
+#3556=ADVANCED_FACE('',(#1140),#206,.T.);
+#3557=ADVANCED_FACE('',(#1141),#207,.T.);
+#3558=ADVANCED_FACE('',(#1142),#208,.T.);
+#3559=ADVANCED_FACE('',(#1143),#209,.T.);
+#3560=ADVANCED_FACE('',(#1144),#957,.F.);
+#3561=ADVANCED_FACE('',(#1145),#210,.F.);
+#3562=ADVANCED_FACE('',(#1146),#211,.F.);
+#3563=ADVANCED_FACE('',(#1147),#212,.T.);
+#3564=ADVANCED_FACE('',(#1148),#213,.F.);
+#3565=ADVANCED_FACE('',(#1149),#214,.F.);
+#3566=ADVANCED_FACE('',(#1150,#236,#237,#238,#239,#240,#241,#242,#243,#244,
+#245,#246,#247,#248,#249,#250,#251,#252,#253,#254,#255,#256,#257,#258,#259),
+#958,.T.);
+#3567=ADVANCED_FACE('',(#1151),#959,.F.);
+#3568=ADVANCED_FACE('',(#1152),#960,.T.);
+#3569=ADVANCED_FACE('',(#1153),#215,.T.);
+#3570=ADVANCED_FACE('',(#1154),#216,.T.);
+#3571=ADVANCED_FACE('',(#1155),#217,.F.);
+#3572=ADVANCED_FACE('',(#1156),#961,.F.);
+#3573=ADVANCED_FACE('',(#1157),#962,.F.);
+#3574=ADVANCED_FACE('',(#1158),#963,.F.);
+#3575=ADVANCED_FACE('',(#1159),#218,.F.);
+#3576=ADVANCED_FACE('',(#1160),#964,.T.);
+#3577=ADVANCED_FACE('',(#1161),#219,.F.);
+#3578=ADVANCED_FACE('',(#1162),#965,.T.);
+#3579=ADVANCED_FACE('',(#1163),#220,.T.);
+#3580=ADVANCED_FACE('',(#1164),#966,.T.);
+#3581=ADVANCED_FACE('',(#1165),#967,.T.);
+#3582=CLOSED_SHELL('',(#3384,#3385,#3386,#3387,#3388,#3389,#3390,#3391,
+#3392,#3393,#3394,#3395,#3396,#3397,#3398,#3399,#3400,#3401,#3402,#3403,
+#3404,#3405,#3406,#3407,#3408,#3409,#3410,#3411,#3412,#3413,#3414,#3415,
+#3416,#3417,#3418,#3419,#3420,#3421,#3422,#3423,#3424,#3425,#3426,#3427,
+#3428,#3429,#3430,#3431,#3432,#3433,#3434,#3435,#3436,#3437,#3438,#3439,
+#3440,#3441,#3442,#3443,#3444,#3445,#3446,#3447,#3448,#3449,#3450,#3451,
+#3452,#3453,#3454,#3455,#3456,#3457,#3458,#3459,#3460,#3461,#3462,#3463,
+#3464,#3465,#3466,#3467,#3468,#3469,#3470,#3471,#3472,#3473,#3474,#3475,
+#3476,#3477,#3478,#3479,#3480,#3481,#3482,#3483,#3484,#3485,#3486,#3487,
+#3488,#3489,#3490,#3491,#3492,#3493,#3494,#3495,#3496,#3497,#3498,#3499,
+#3500,#3501,#3502,#3503,#3504,#3505,#3506,#3507,#3508,#3509,#3510,#3511,
+#3512,#3513,#3514,#3515,#3516,#3517,#3518,#3519,#3520,#3521,#3522,#3523,
+#3524,#3525,#3526,#3527,#3528,#3529,#3530,#3531,#3532,#3533,#3534,#3535,
+#3536,#3537,#3538,#3539,#3540,#3541,#3542,#3543,#3544,#3545,#3546,#3547,
+#3548,#3549,#3550,#3551,#3552,#3553,#3554,#3555,#3556,#3557,#3558,#3559,
+#3560,#3561,#3562,#3563,#3564,#3565,#3566,#3567,#3568,#3569,#3570,#3571,
+#3572,#3573,#3574,#3575,#3576,#3577,#3578,#3579,#3580,#3581));
+#3583=DERIVED_UNIT_ELEMENT(#3586,1.);
+#3584=DERIVED_UNIT_ELEMENT(#7525,-3.);
+#3585=DIMENSIONAL_EXPONENTS(0.,1.,0.,0.,0.,0.,0.);
+#3586=(
+CONVERSION_BASED_UNIT('gram',#3588)
+MASS_UNIT()
+NAMED_UNIT(#3585)
+);
+#3587=(
+MASS_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.KILO.,.GRAM.)
+);
+#3588=MASS_MEASURE_WITH_UNIT(MASS_MEASURE(0.001),#3587);
+#3589=DERIVED_UNIT((#3583,#3584));
+#3590=MEASURE_REPRESENTATION_ITEM('density measure',
+POSITIVE_RATIO_MEASURE(1.),#3589);
+#3591=PROPERTY_DEFINITION_REPRESENTATION(#3596,#3593);
+#3592=PROPERTY_DEFINITION_REPRESENTATION(#3597,#3594);
+#3593=REPRESENTATION('material name',(#3595),#7522);
+#3594=REPRESENTATION('density',(#3590),#7522);
+#3595=DESCRIPTIVE_REPRESENTATION_ITEM('Generisch','Generisch');
+#3596=PROPERTY_DEFINITION('material property','material name',#7532);
+#3597=PROPERTY_DEFINITION('material property','density of part',#7532);
+#3598=DATE_TIME_ROLE('creation_date');
+#3599=APPLIED_DATE_AND_TIME_ASSIGNMENT(#3600,#3598,(#7532));
+#3600=DATE_AND_TIME(#3601,#3602);
+#3601=CALENDAR_DATE(2025,6,1);
+#3602=LOCAL_TIME(0,0,0.,#3603);
+#3603=COORDINATED_UNIVERSAL_TIME_OFFSET(0,0,.BEHIND.);
+#3604=AXIS2_PLACEMENT_3D('',#4990,#3966,#3967);
+#3605=AXIS2_PLACEMENT_3D('',#5024,#3968,#3969);
+#3606=AXIS2_PLACEMENT_3D('',#5111,#3970,#3971);
+#3607=AXIS2_PLACEMENT_3D('',#5340,#3972,#3973);
+#3608=AXIS2_PLACEMENT_3D('',#5389,#3980,#3981);
+#3609=AXIS2_PLACEMENT_3D('',#5390,#3982,#3983);
+#3610=AXIS2_PLACEMENT_3D('',#5392,#3984,#3985);
+#3611=AXIS2_PLACEMENT_3D('',#5393,#3986,#3987);
+#3612=AXIS2_PLACEMENT_3D('',#5394,#3988,#3989);
+#3613=AXIS2_PLACEMENT_3D('',#5422,#3990,#3991);
+#3614=AXIS2_PLACEMENT_3D('',#5423,#3992,#3993);
+#3615=AXIS2_PLACEMENT_3D('',#5432,#3998,#3999);
+#3616=AXIS2_PLACEMENT_3D('',#5438,#4003,#4004);
+#3617=AXIS2_PLACEMENT_3D('',#5444,#4008,#4009);
+#3618=AXIS2_PLACEMENT_3D('',#5447,#4012,#4013);
+#3619=AXIS2_PLACEMENT_3D('',#5448,#4014,#4015);
+#3620=AXIS2_PLACEMENT_3D('',#5457,#4020,#4021);
+#3621=AXIS2_PLACEMENT_3D('',#5463,#4025,#4026);
+#3622=AXIS2_PLACEMENT_3D('',#5469,#4030,#4031);
+#3623=AXIS2_PLACEMENT_3D('',#5472,#4034,#4035);
+#3624=AXIS2_PLACEMENT_3D('',#5473,#4036,#4037);
+#3625=AXIS2_PLACEMENT_3D('',#5482,#4042,#4043);
+#3626=AXIS2_PLACEMENT_3D('',#5488,#4047,#4048);
+#3627=AXIS2_PLACEMENT_3D('',#5494,#4052,#4053);
+#3628=AXIS2_PLACEMENT_3D('',#5497,#4056,#4057);
+#3629=AXIS2_PLACEMENT_3D('',#5498,#4058,#4059);
+#3630=AXIS2_PLACEMENT_3D('',#5507,#4064,#4065);
+#3631=AXIS2_PLACEMENT_3D('',#5513,#4069,#4070);
+#3632=AXIS2_PLACEMENT_3D('',#5519,#4074,#4075);
+#3633=AXIS2_PLACEMENT_3D('',#5522,#4078,#4079);
+#3634=AXIS2_PLACEMENT_3D('',#5523,#4080,#4081);
+#3635=AXIS2_PLACEMENT_3D('',#5532,#4086,#4087);
+#3636=AXIS2_PLACEMENT_3D('',#5538,#4091,#4092);
+#3637=AXIS2_PLACEMENT_3D('',#5544,#4096,#4097);
+#3638=AXIS2_PLACEMENT_3D('',#5547,#4100,#4101);
+#3639=AXIS2_PLACEMENT_3D('',#5548,#4102,#4103);
+#3640=AXIS2_PLACEMENT_3D('',#5550,#4104,#4105);
+#3641=AXIS2_PLACEMENT_3D('',#5554,#4107,#4108);
+#3642=AXIS2_PLACEMENT_3D('',#5566,#4109,#4110);
+#3643=AXIS2_PLACEMENT_3D('',#5567,#4111,#4112);
+#3644=AXIS2_PLACEMENT_3D('',#5569,#4113,#4114);
+#3645=AXIS2_PLACEMENT_3D('',#5573,#4116,#4117);
+#3646=AXIS2_PLACEMENT_3D('',#5585,#4118,#4119);
+#3647=AXIS2_PLACEMENT_3D('',#5586,#4120,#4121);
+#3648=AXIS2_PLACEMENT_3D('',#5616,#4128,#4129);
+#3649=AXIS2_PLACEMENT_3D('',#5621,#4131,#4132);
+#3650=AXIS2_PLACEMENT_3D('',#5624,#4134,#4135);
+#3651=AXIS2_PLACEMENT_3D('',#5625,#4136,#4137);
+#3652=AXIS2_PLACEMENT_3D('',#5630,#4139,#4140);
+#3653=AXIS2_PLACEMENT_3D('',#5633,#4142,#4143);
+#3654=AXIS2_PLACEMENT_3D('',#5634,#4144,#4145);
+#3655=AXIS2_PLACEMENT_3D('',#5640,#4148,#4149);
+#3656=AXIS2_PLACEMENT_3D('',#5642,#4150,#4151);
+#3657=AXIS2_PLACEMENT_3D('',#5646,#4153,#4154);
+#3658=AXIS2_PLACEMENT_3D('',#5648,#4155,#4156);
+#3659=AXIS2_PLACEMENT_3D('',#5650,#4157,#4158);
+#3660=AXIS2_PLACEMENT_3D('',#5652,#4159,#4160);
+#3661=AXIS2_PLACEMENT_3D('',#5654,#4161,#4162);
+#3662=AXIS2_PLACEMENT_3D('',#5656,#4163,#4164);
+#3663=AXIS2_PLACEMENT_3D('',#5658,#4165,#4166);
+#3664=AXIS2_PLACEMENT_3D('',#5662,#4168,#4169);
+#3665=AXIS2_PLACEMENT_3D('',#5664,#4170,#4171);
+#3666=AXIS2_PLACEMENT_3D('',#5671,#4175,#4176);
+#3667=AXIS2_PLACEMENT_3D('',#5675,#4178,#4179);
+#3668=AXIS2_PLACEMENT_3D('',#5677,#4180,#4181);
+#3669=AXIS2_PLACEMENT_3D('',#5679,#4182,#4183);
+#3670=AXIS2_PLACEMENT_3D('',#5681,#4184,#4185);
+#3671=AXIS2_PLACEMENT_3D('',#5683,#4186,#4187);
+#3672=AXIS2_PLACEMENT_3D('',#5687,#4189,#4190);
+#3673=AXIS2_PLACEMENT_3D('',#5689,#4191,#4192);
+#3674=AXIS2_PLACEMENT_3D('',#5691,#4193,#4194);
+#3675=AXIS2_PLACEMENT_3D('',#5693,#4195,#4196);
+#3676=AXIS2_PLACEMENT_3D('',#5695,#4197,#4198);
+#3677=AXIS2_PLACEMENT_3D('',#5699,#4200,#4201);
+#3678=AXIS2_PLACEMENT_3D('',#5701,#4202,#4203);
+#3679=AXIS2_PLACEMENT_3D('',#5703,#4204,#4205);
+#3680=AXIS2_PLACEMENT_3D('',#5705,#4206,#4207);
+#3681=AXIS2_PLACEMENT_3D('',#5707,#4208,#4209);
+#3682=AXIS2_PLACEMENT_3D('',#5711,#4211,#4212);
+#3683=AXIS2_PLACEMENT_3D('',#5714,#4214,#4215);
+#3684=AXIS2_PLACEMENT_3D('',#5716,#4216,#4217);
+#3685=AXIS2_PLACEMENT_3D('',#5718,#4218,#4219);
+#3686=AXIS2_PLACEMENT_3D('',#5720,#4220,#4221);
+#3687=AXIS2_PLACEMENT_3D('',#5721,#4222,#4223);
+#3688=AXIS2_PLACEMENT_3D('',#5728,#4228,#4229);
+#3689=AXIS2_PLACEMENT_3D('',#5730,#4230,#4231);
+#3690=AXIS2_PLACEMENT_3D('',#5732,#4232,#4233);
+#3691=AXIS2_PLACEMENT_3D('',#5733,#4234,#4235);
+#3692=AXIS2_PLACEMENT_3D('',#5734,#4236,#4237);
+#3693=AXIS2_PLACEMENT_3D('',#5736,#4238,#4239);
+#3694=AXIS2_PLACEMENT_3D('',#5934,#4241,#4242);
+#3695=AXIS2_PLACEMENT_3D('',#5937,#4243,#4244);
+#3696=AXIS2_PLACEMENT_3D('',#5940,#4247,#4248);
+#3697=AXIS2_PLACEMENT_3D('',#5943,#4249,#4250);
+#3698=AXIS2_PLACEMENT_3D('',#5944,#4251,#4252);
+#3699=AXIS2_PLACEMENT_3D('',#5945,#4253,#4254);
+#3700=AXIS2_PLACEMENT_3D('',#5946,#4255,#4256);
+#3701=AXIS2_PLACEMENT_3D('',#5949,#4258,#4259);
+#3702=AXIS2_PLACEMENT_3D('',#6121,#4260,#4261);
+#3703=AXIS2_PLACEMENT_3D('',#6123,#4263,#4264);
+#3704=AXIS2_PLACEMENT_3D('',#6126,#4265,#4266);
+#3705=AXIS2_PLACEMENT_3D('',#6129,#4269,#4270);
+#3706=AXIS2_PLACEMENT_3D('',#6131,#4271,#4272);
+#3707=AXIS2_PLACEMENT_3D('',#6135,#4275,#4276);
+#3708=AXIS2_PLACEMENT_3D('',#6142,#4277,#4278);
+#3709=AXIS2_PLACEMENT_3D('',#6143,#4279,#4280);
+#3710=AXIS2_PLACEMENT_3D('',#6144,#4281,#4282);
+#3711=AXIS2_PLACEMENT_3D('',#6154,#4284,#4285);
+#3712=AXIS2_PLACEMENT_3D('',#6156,#4286,#4287);
+#3713=AXIS2_PLACEMENT_3D('',#6158,#4288,#4289);
+#3714=AXIS2_PLACEMENT_3D('',#6162,#4291,#4292);
+#3715=AXIS2_PLACEMENT_3D('',#6164,#4293,#4294);
+#3716=AXIS2_PLACEMENT_3D('',#6166,#4295,#4296);
+#3717=AXIS2_PLACEMENT_3D('',#6174,#4300,#4301);
+#3718=AXIS2_PLACEMENT_3D('',#6176,#4302,#4303);
+#3719=AXIS2_PLACEMENT_3D('',#6178,#4304,#4305);
+#3720=AXIS2_PLACEMENT_3D('',#6220,#4327,#4328);
+#3721=AXIS2_PLACEMENT_3D('',#6221,#4329,#4330);
+#3722=AXIS2_PLACEMENT_3D('',#6224,#4332,#4333);
+#3723=AXIS2_PLACEMENT_3D('',#6225,#4334,#4335);
+#3724=AXIS2_PLACEMENT_3D('',#6228,#4336,#4337);
+#3725=AXIS2_PLACEMENT_3D('',#6232,#4339,#4340);
+#3726=AXIS2_PLACEMENT_3D('',#6274,#4342,#4343);
+#3727=AXIS2_PLACEMENT_3D('',#6276,#4344,#4345);
+#3728=AXIS2_PLACEMENT_3D('',#6277,#4346,#4347);
+#3729=AXIS2_PLACEMENT_3D('',#6278,#4348,#4349);
+#3730=AXIS2_PLACEMENT_3D('',#6280,#4350,#4351);
+#3731=AXIS2_PLACEMENT_3D('',#6285,#4354,#4355);
+#3732=AXIS2_PLACEMENT_3D('',#6288,#4358,#4359);
+#3733=AXIS2_PLACEMENT_3D('',#6291,#4360,#4361);
+#3734=AXIS2_PLACEMENT_3D('',#6292,#4362,#4363);
+#3735=AXIS2_PLACEMENT_3D('',#6293,#4364,#4365);
+#3736=AXIS2_PLACEMENT_3D('',#6294,#4366,#4367);
+#3737=AXIS2_PLACEMENT_3D('',#6296,#4368,#4369);
+#3738=AXIS2_PLACEMENT_3D('',#6298,#4371,#4372);
+#3739=AXIS2_PLACEMENT_3D('',#6300,#4373,#4374);
+#3740=AXIS2_PLACEMENT_3D('',#6301,#4375,#4376);
+#3741=AXIS2_PLACEMENT_3D('',#6302,#4377,#4378);
+#3742=AXIS2_PLACEMENT_3D('',#6303,#4379,#4380);
+#3743=AXIS2_PLACEMENT_3D('',#6304,#4381,#4382);
+#3744=AXIS2_PLACEMENT_3D('',#6306,#4383,#4384);
+#3745=AXIS2_PLACEMENT_3D('',#6307,#4385,#4386);
+#3746=AXIS2_PLACEMENT_3D('',#6308,#4387,#4388);
+#3747=AXIS2_PLACEMENT_3D('',#6309,#4389,#4390);
+#3748=AXIS2_PLACEMENT_3D('',#6311,#4392,#4393);
+#3749=AXIS2_PLACEMENT_3D('',#6313,#4394,#4395);
+#3750=AXIS2_PLACEMENT_3D('',#6314,#4396,#4397);
+#3751=AXIS2_PLACEMENT_3D('',#6315,#4398,#4399);
+#3752=AXIS2_PLACEMENT_3D('',#6316,#4400,#4401);
+#3753=AXIS2_PLACEMENT_3D('',#6317,#4402,#4403);
+#3754=AXIS2_PLACEMENT_3D('',#6320,#4404,#4405);
+#3755=AXIS2_PLACEMENT_3D('',#6321,#4406,#4407);
+#3756=AXIS2_PLACEMENT_3D('',#6322,#4408,#4409);
+#3757=AXIS2_PLACEMENT_3D('',#6323,#4410,#4411);
+#3758=AXIS2_PLACEMENT_3D('',#6325,#4413,#4414);
+#3759=AXIS2_PLACEMENT_3D('',#6327,#4415,#4416);
+#3760=AXIS2_PLACEMENT_3D('',#6328,#4417,#4418);
+#3761=AXIS2_PLACEMENT_3D('',#6329,#4419,#4420);
+#3762=AXIS2_PLACEMENT_3D('',#6331,#4421,#4422);
+#3763=AXIS2_PLACEMENT_3D('',#6332,#4423,#4424);
+#3764=AXIS2_PLACEMENT_3D('',#6333,#4425,#4426);
+#3765=AXIS2_PLACEMENT_3D('',#6335,#4427,#4428);
+#3766=AXIS2_PLACEMENT_3D('',#6337,#4430,#4431);
+#3767=AXIS2_PLACEMENT_3D('',#6339,#4432,#4433);
+#3768=AXIS2_PLACEMENT_3D('',#6340,#4434,#4435);
+#3769=AXIS2_PLACEMENT_3D('',#6341,#4436,#4437);
+#3770=AXIS2_PLACEMENT_3D('',#6342,#4438,#4439);
+#3771=AXIS2_PLACEMENT_3D('',#6343,#4440,#4441);
+#3772=AXIS2_PLACEMENT_3D('',#6346,#4444,#4445);
+#3773=AXIS2_PLACEMENT_3D('',#6348,#4447,#4448);
+#3774=AXIS2_PLACEMENT_3D('',#6350,#4450,#4451);
+#3775=AXIS2_PLACEMENT_3D('',#6353,#4454,#4455);
+#3776=AXIS2_PLACEMENT_3D('',#6358,#4458,#4459);
+#3777=AXIS2_PLACEMENT_3D('',#6361,#4462,#4463);
+#3778=AXIS2_PLACEMENT_3D('',#6362,#4464,#4465);
+#3779=AXIS2_PLACEMENT_3D('',#6364,#4467,#4468);
+#3780=AXIS2_PLACEMENT_3D('',#6367,#4471,#4472);
+#3781=AXIS2_PLACEMENT_3D('',#6368,#4473,#4474);
+#3782=AXIS2_PLACEMENT_3D('',#6370,#4475,#4476);
+#3783=AXIS2_PLACEMENT_3D('',#6373,#4478,#4479);
+#3784=AXIS2_PLACEMENT_3D('',#6374,#4480,#4481);
+#3785=AXIS2_PLACEMENT_3D('',#6375,#4482,#4483);
+#3786=AXIS2_PLACEMENT_3D('',#6378,#4485,#4486);
+#3787=AXIS2_PLACEMENT_3D('',#6379,#4487,#4488);
+#3788=AXIS2_PLACEMENT_3D('',#6380,#4489,#4490);
+#3789=AXIS2_PLACEMENT_3D('',#6382,#4491,#4492);
+#3790=AXIS2_PLACEMENT_3D('',#6385,#4494,#4495);
+#3791=AXIS2_PLACEMENT_3D('',#6386,#4496,#4497);
+#3792=AXIS2_PLACEMENT_3D('',#6387,#4498,#4499);
+#3793=AXIS2_PLACEMENT_3D('',#6389,#4500,#4501);
+#3794=AXIS2_PLACEMENT_3D('',#6392,#4503,#4504);
+#3795=AXIS2_PLACEMENT_3D('',#6393,#4505,#4506);
+#3796=AXIS2_PLACEMENT_3D('',#6435,#4507,#4508);
+#3797=AXIS2_PLACEMENT_3D('',#6466,#4509,#4510);
+#3798=AXIS2_PLACEMENT_3D('',#6469,#4512,#4513);
+#3799=AXIS2_PLACEMENT_3D('',#6470,#4514,#4515);
+#3800=AXIS2_PLACEMENT_3D('',#6473,#4517,#4518);
+#3801=AXIS2_PLACEMENT_3D('',#6474,#4519,#4520);
+#3802=AXIS2_PLACEMENT_3D('',#6476,#4521,#4522);
+#3803=AXIS2_PLACEMENT_3D('',#6478,#4523,#4524);
+#3804=AXIS2_PLACEMENT_3D('',#6479,#4525,#4526);
+#3805=AXIS2_PLACEMENT_3D('',#6508,#4527,#4528);
+#3806=AXIS2_PLACEMENT_3D('',#6509,#4529,#4530);
+#3807=AXIS2_PLACEMENT_3D('',#6510,#4531,#4532);
+#3808=AXIS2_PLACEMENT_3D('',#6513,#4534,#4535);
+#3809=AXIS2_PLACEMENT_3D('',#6514,#4536,#4537);
+#3810=AXIS2_PLACEMENT_3D('',#6516,#4538,#4539);
+#3811=AXIS2_PLACEMENT_3D('',#6564,#4541,#4542);
+#3812=AXIS2_PLACEMENT_3D('',#6952,#4543,#4544);
+#3813=AXIS2_PLACEMENT_3D('',#6955,#4546,#4547);
+#3814=AXIS2_PLACEMENT_3D('',#6956,#4548,#4549);
+#3815=AXIS2_PLACEMENT_3D('',#6958,#4550,#4551);
+#3816=AXIS2_PLACEMENT_3D('',#6960,#4553,#4554);
+#3817=AXIS2_PLACEMENT_3D('',#6961,#4555,#4556);
+#3818=AXIS2_PLACEMENT_3D('',#6962,#4557,#4558);
+#3819=AXIS2_PLACEMENT_3D('',#6963,#4559,#4560);
+#3820=AXIS2_PLACEMENT_3D('',#6964,#4561,#4562);
+#3821=AXIS2_PLACEMENT_3D('',#6965,#4563,#4564);
+#3822=AXIS2_PLACEMENT_3D('',#6966,#4565,#4566);
+#3823=AXIS2_PLACEMENT_3D('',#6967,#4567,#4568);
+#3824=AXIS2_PLACEMENT_3D('',#6970,#4570,#4571);
+#3825=AXIS2_PLACEMENT_3D('',#6971,#4572,#4573);
+#3826=AXIS2_PLACEMENT_3D('',#6972,#4574,#4575);
+#3827=AXIS2_PLACEMENT_3D('',#6975,#4577,#4578);
+#3828=AXIS2_PLACEMENT_3D('',#6976,#4579,#4580);
+#3829=AXIS2_PLACEMENT_3D('',#6977,#4581,#4582);
+#3830=AXIS2_PLACEMENT_3D('',#6980,#4584,#4585);
+#3831=AXIS2_PLACEMENT_3D('',#6981,#4586,#4587);
+#3832=AXIS2_PLACEMENT_3D('',#6982,#4588,#4589);
+#3833=AXIS2_PLACEMENT_3D('',#6985,#4591,#4592);
+#3834=AXIS2_PLACEMENT_3D('',#6986,#4593,#4594);
+#3835=AXIS2_PLACEMENT_3D('',#6987,#4595,#4596);
+#3836=AXIS2_PLACEMENT_3D('',#6993,#4600,#4601);
+#3837=AXIS2_PLACEMENT_3D('',#6997,#4604,#4605);
+#3838=AXIS2_PLACEMENT_3D('',#7001,#4608,#4609);
+#3839=AXIS2_PLACEMENT_3D('',#7003,#4611,#4612);
+#3840=AXIS2_PLACEMENT_3D('',#7009,#4616,#4617);
+#3841=AXIS2_PLACEMENT_3D('',#7013,#4620,#4621);
+#3842=AXIS2_PLACEMENT_3D('',#7017,#4624,#4625);
+#3843=AXIS2_PLACEMENT_3D('',#7019,#4627,#4628);
+#3844=AXIS2_PLACEMENT_3D('',#7025,#4632,#4633);
+#3845=AXIS2_PLACEMENT_3D('',#7029,#4636,#4637);
+#3846=AXIS2_PLACEMENT_3D('',#7033,#4640,#4641);
+#3847=AXIS2_PLACEMENT_3D('',#7035,#4643,#4644);
+#3848=AXIS2_PLACEMENT_3D('',#7041,#4648,#4649);
+#3849=AXIS2_PLACEMENT_3D('',#7045,#4652,#4653);
+#3850=AXIS2_PLACEMENT_3D('',#7049,#4656,#4657);
+#3851=AXIS2_PLACEMENT_3D('',#7051,#4659,#4660);
+#3852=AXIS2_PLACEMENT_3D('',#7057,#4664,#4665);
+#3853=AXIS2_PLACEMENT_3D('',#7061,#4668,#4669);
+#3854=AXIS2_PLACEMENT_3D('',#7065,#4672,#4673);
+#3855=AXIS2_PLACEMENT_3D('',#7067,#4675,#4676);
+#3856=AXIS2_PLACEMENT_3D('',#7076,#4681,#4682);
+#3857=AXIS2_PLACEMENT_3D('',#7082,#4686,#4687);
+#3858=AXIS2_PLACEMENT_3D('',#7088,#4691,#4692);
+#3859=AXIS2_PLACEMENT_3D('',#7091,#4695,#4696);
+#3860=AXIS2_PLACEMENT_3D('',#7092,#4697,#4698);
+#3861=AXIS2_PLACEMENT_3D('',#7101,#4703,#4704);
+#3862=AXIS2_PLACEMENT_3D('',#7107,#4708,#4709);
+#3863=AXIS2_PLACEMENT_3D('',#7113,#4713,#4714);
+#3864=AXIS2_PLACEMENT_3D('',#7116,#4717,#4718);
+#3865=AXIS2_PLACEMENT_3D('',#7117,#4719,#4720);
+#3866=AXIS2_PLACEMENT_3D('',#7126,#4725,#4726);
+#3867=AXIS2_PLACEMENT_3D('',#7132,#4730,#4731);
+#3868=AXIS2_PLACEMENT_3D('',#7138,#4735,#4736);
+#3869=AXIS2_PLACEMENT_3D('',#7141,#4739,#4740);
+#3870=AXIS2_PLACEMENT_3D('',#7142,#4741,#4742);
+#3871=AXIS2_PLACEMENT_3D('',#7151,#4747,#4748);
+#3872=AXIS2_PLACEMENT_3D('',#7157,#4752,#4753);
+#3873=AXIS2_PLACEMENT_3D('',#7163,#4757,#4758);
+#3874=AXIS2_PLACEMENT_3D('',#7166,#4761,#4762);
+#3875=AXIS2_PLACEMENT_3D('',#7167,#4763,#4764);
+#3876=AXIS2_PLACEMENT_3D('',#7176,#4769,#4770);
+#3877=AXIS2_PLACEMENT_3D('',#7182,#4774,#4775);
+#3878=AXIS2_PLACEMENT_3D('',#7188,#4779,#4780);
+#3879=AXIS2_PLACEMENT_3D('',#7191,#4783,#4784);
+#3880=AXIS2_PLACEMENT_3D('',#7192,#4785,#4786);
+#3881=AXIS2_PLACEMENT_3D('',#7194,#4787,#4788);
+#3882=AXIS2_PLACEMENT_3D('',#7197,#4790,#4791);
+#3883=AXIS2_PLACEMENT_3D('',#7198,#4792,#4793);
+#3884=AXIS2_PLACEMENT_3D('',#7199,#4794,#4795);
+#3885=AXIS2_PLACEMENT_3D('',#7201,#4796,#4797);
+#3886=AXIS2_PLACEMENT_3D('',#7204,#4799,#4800);
+#3887=AXIS2_PLACEMENT_3D('',#7205,#4801,#4802);
+#3888=AXIS2_PLACEMENT_3D('',#7206,#4803,#4804);
+#3889=AXIS2_PLACEMENT_3D('',#7208,#4805,#4806);
+#3890=AXIS2_PLACEMENT_3D('',#7211,#4808,#4809);
+#3891=AXIS2_PLACEMENT_3D('',#7212,#4810,#4811);
+#3892=AXIS2_PLACEMENT_3D('',#7213,#4812,#4813);
+#3893=AXIS2_PLACEMENT_3D('',#7215,#4814,#4815);
+#3894=AXIS2_PLACEMENT_3D('',#7218,#4817,#4818);
+#3895=AXIS2_PLACEMENT_3D('',#7219,#4819,#4820);
+#3896=AXIS2_PLACEMENT_3D('',#7220,#4821,#4822);
+#3897=AXIS2_PLACEMENT_3D('',#7222,#4823,#4824);
+#3898=AXIS2_PLACEMENT_3D('',#7225,#4826,#4827);
+#3899=AXIS2_PLACEMENT_3D('',#7226,#4828,#4829);
+#3900=AXIS2_PLACEMENT_3D('',#7227,#4830,#4831);
+#3901=AXIS2_PLACEMENT_3D('',#7232,#4834,#4835);
+#3902=AXIS2_PLACEMENT_3D('',#7233,#4836,#4837);
+#3903=AXIS2_PLACEMENT_3D('',#7234,#4838,#4839);
+#3904=AXIS2_PLACEMENT_3D('',#7238,#4841,#4842);
+#3905=AXIS2_PLACEMENT_3D('',#7240,#4844,#4845);
+#3906=AXIS2_PLACEMENT_3D('',#7241,#4846,#4847);
+#3907=AXIS2_PLACEMENT_3D('',#7242,#4848,#4849);
+#3908=AXIS2_PLACEMENT_3D('',#7243,#4850,#4851);
+#3909=AXIS2_PLACEMENT_3D('',#7247,#4853,#4854);
+#3910=AXIS2_PLACEMENT_3D('',#7249,#4856,#4857);
+#3911=AXIS2_PLACEMENT_3D('',#7254,#4860,#4861);
+#3912=AXIS2_PLACEMENT_3D('',#7255,#4862,#4863);
+#3913=AXIS2_PLACEMENT_3D('',#7259,#4865,#4866);
+#3914=AXIS2_PLACEMENT_3D('',#7261,#4868,#4869);
+#3915=AXIS2_PLACEMENT_3D('',#7265,#4872,#4873);
+#3916=AXIS2_PLACEMENT_3D('',#7267,#4874,#4875);
+#3917=AXIS2_PLACEMENT_3D('',#7269,#4877,#4878);
+#3918=AXIS2_PLACEMENT_3D('',#7272,#4880,#4881);
+#3919=AXIS2_PLACEMENT_3D('',#7273,#4882,#4883);
+#3920=AXIS2_PLACEMENT_3D('',#7276,#4886,#4887);
+#3921=AXIS2_PLACEMENT_3D('',#7278,#4888,#4889);
+#3922=AXIS2_PLACEMENT_3D('',#7280,#4891,#4892);
+#3923=AXIS2_PLACEMENT_3D('',#7281,#4893,#4894);
+#3924=AXIS2_PLACEMENT_3D('',#7282,#4895,#4896);
+#3925=AXIS2_PLACEMENT_3D('',#7284,#4897,#4898);
+#3926=AXIS2_PLACEMENT_3D('',#7291,#4902,#4903);
+#3927=AXIS2_PLACEMENT_3D('',#7293,#4905,#4906);
+#3928=AXIS2_PLACEMENT_3D('',#7294,#4907,#4908);
+#3929=AXIS2_PLACEMENT_3D('',#7295,#4909,#4910);
+#3930=AXIS2_PLACEMENT_3D('',#7297,#4912,#4913);
+#3931=AXIS2_PLACEMENT_3D('',#7300,#4916,#4917);
+#3932=AXIS2_PLACEMENT_3D('',#7301,#4918,#4919);
+#3933=AXIS2_PLACEMENT_3D('',#7303,#4921,#4922);
+#3934=AXIS2_PLACEMENT_3D('',#7305,#4924,#4925);
+#3935=AXIS2_PLACEMENT_3D('',#7307,#4927,#4928);
+#3936=AXIS2_PLACEMENT_3D('',#7309,#4930,#4931);
+#3937=AXIS2_PLACEMENT_3D('',#7310,#4932,#4933);
+#3938=AXIS2_PLACEMENT_3D('',#7311,#4934,#4935);
+#3939=AXIS2_PLACEMENT_3D('',#7312,#4936,#4937);
+#3940=AXIS2_PLACEMENT_3D('',#7313,#4938,#4939);
+#3941=AXIS2_PLACEMENT_3D('',#7314,#4940,#4941);
+#3942=AXIS2_PLACEMENT_3D('',#7315,#4942,#4943);
+#3943=AXIS2_PLACEMENT_3D('',#7316,#4944,#4945);
+#3944=AXIS2_PLACEMENT_3D('',#7319,#4946,#4947);
+#3945=AXIS2_PLACEMENT_3D('',#7322,#4948,#4949);
+#3946=AXIS2_PLACEMENT_3D('',#7323,#4950,#4951);
+#3947=AXIS2_PLACEMENT_3D('',#7326,#4952,#4953);
+#3948=AXIS2_PLACEMENT_3D('',#7327,#4954,#4955);
+#3949=AXIS2_PLACEMENT_3D('',#7330,#4956,#4957);
+#3950=AXIS2_PLACEMENT_3D('',#7331,#4958,#4959);
+#3951=AXIS2_PLACEMENT_3D('',#7336,#4960,#4961);
+#3952=AXIS2_PLACEMENT_3D('',#7339,#4962,#4963);
+#3953=AXIS2_PLACEMENT_3D('',#7342,#4964,#4965);
+#3954=AXIS2_PLACEMENT_3D('',#7343,#4966,#4967);
+#3955=AXIS2_PLACEMENT_3D('',#7344,#4968,#4969);
+#3956=AXIS2_PLACEMENT_3D('',#7345,#4970,#4971);
+#3957=AXIS2_PLACEMENT_3D('',#7346,#4972,#4973);
+#3958=AXIS2_PLACEMENT_3D('',#7463,#4974,#4975);
+#3959=AXIS2_PLACEMENT_3D('',#7464,#4976,#4977);
+#3960=AXIS2_PLACEMENT_3D('',#7465,#4978,#4979);
+#3961=AXIS2_PLACEMENT_3D('',#7466,#4980,#4981);
+#3962=AXIS2_PLACEMENT_3D('',#7467,#4982,#4983);
+#3963=AXIS2_PLACEMENT_3D('',#7468,#4984,#4985);
+#3964=AXIS2_PLACEMENT_3D('',#7469,#4986,#4987);
+#3965=AXIS2_PLACEMENT_3D('',#7470,#4988,#4989);
+#3966=DIRECTION('axis',(0.,0.,1.));
+#3967=DIRECTION('refdir',(1.,0.,0.));
+#3968=DIRECTION('center_axis',(-0.319806824553403,-0.899205513693041,-0.29858506177152));
+#3969=DIRECTION('ref_axis',(-0.942185148849968,0.335092741321806,0.));
+#3970=DIRECTION('center_axis',(0.000113588040247808,-0.999999993445482,
+-1.43803076672257E-5));
+#3971=DIRECTION('ref_axis',(-0.999999993548879,-0.000113588040259553,0.));
+#3972=DIRECTION('center_axis',(0.,1.,0.));
+#3973=DIRECTION('ref_axis',(0.,0.,1.));
+#3974=DIRECTION('',(0.,0.,1.));
+#3975=DIRECTION('',(0.,0.,1.));
+#3976=DIRECTION('',(-1.,0.,0.));
+#3977=DIRECTION('',(0.,0.,-1.));
+#3978=DIRECTION('',(0.,0.,-1.));
+#3979=DIRECTION('',(1.,0.,0.));
+#3980=DIRECTION('center_axis',(0.,0.,1.));
+#3981=DIRECTION('ref_axis',(1.,0.,0.));
+#3982=DIRECTION('center_axis',(0.,0.,1.));
+#3983=DIRECTION('ref_axis',(1.,0.,0.));
+#3984=DIRECTION('center_axis',(0.,0.,-1.));
+#3985=DIRECTION('ref_axis',(1.,0.,0.));
+#3986=DIRECTION('center_axis',(0.,0.,1.));
+#3987=DIRECTION('ref_axis',(-1.83697019872103E-16,1.,0.));
+#3988=DIRECTION('center_axis',(0.,0.,-1.));
+#3989=DIRECTION('ref_axis',(1.,0.,0.));
+#3990=DIRECTION('center_axis',(0.,0.,-1.));
+#3991=DIRECTION('ref_axis',(1.,0.,0.));
+#3992=DIRECTION('center_axis',(1.,-1.94847982108965E-15,0.));
+#3993=DIRECTION('ref_axis',(-1.94847982108965E-15,-1.,0.));
+#3994=DIRECTION('',(-1.94847982108965E-15,-1.,0.));
+#3995=DIRECTION('',(0.,0.,-1.));
+#3996=DIRECTION('',(-1.94847982108965E-15,-1.,0.));
+#3997=DIRECTION('',(0.,0.,-1.));
+#3998=DIRECTION('center_axis',(0.,1.,0.));
+#3999=DIRECTION('ref_axis',(1.,0.,0.));
+#4000=DIRECTION('',(1.,0.,0.));
+#4001=DIRECTION('',(0.,0.,-1.));
+#4002=DIRECTION('',(1.,0.,0.));
+#4003=DIRECTION('center_axis',(-1.,0.,0.));
+#4004=DIRECTION('ref_axis',(0.,1.,0.));
+#4005=DIRECTION('',(0.,1.,0.));
+#4006=DIRECTION('',(0.,0.,-1.));
+#4007=DIRECTION('',(0.,1.,0.));
+#4008=DIRECTION('center_axis',(0.,-1.,0.));
+#4009=DIRECTION('ref_axis',(-1.,0.,0.));
+#4010=DIRECTION('',(-1.,0.,0.));
+#4011=DIRECTION('',(-1.,0.,0.));
+#4012=DIRECTION('center_axis',(0.,0.,-1.));
+#4013=DIRECTION('ref_axis',(-1.,0.,0.));
+#4014=DIRECTION('center_axis',(1.,-3.20512014189297E-16,0.));
+#4015=DIRECTION('ref_axis',(-3.20512014189297E-16,-1.,0.));
+#4016=DIRECTION('',(-3.20512014189297E-16,-1.,0.));
+#4017=DIRECTION('',(0.,0.,-1.));
+#4018=DIRECTION('',(-3.20512014189297E-16,-1.,0.));
+#4019=DIRECTION('',(0.,0.,-1.));
+#4020=DIRECTION('center_axis',(0.,1.,0.));
+#4021=DIRECTION('ref_axis',(1.,0.,0.));
+#4022=DIRECTION('',(1.,0.,0.));
+#4023=DIRECTION('',(0.,0.,-1.));
+#4024=DIRECTION('',(1.,0.,0.));
+#4025=DIRECTION('center_axis',(-1.,-2.46716227694479E-16,0.));
+#4026=DIRECTION('ref_axis',(-2.46716227694479E-16,1.,0.));
+#4027=DIRECTION('',(-2.46716227694479E-16,1.,0.));
+#4028=DIRECTION('',(0.,0.,-1.));
+#4029=DIRECTION('',(-2.46716227694479E-16,1.,0.));
+#4030=DIRECTION('center_axis',(0.,-1.,0.));
+#4031=DIRECTION('ref_axis',(-1.,0.,0.));
+#4032=DIRECTION('',(-1.,0.,0.));
+#4033=DIRECTION('',(-1.,0.,0.));
+#4034=DIRECTION('center_axis',(0.,0.,-1.));
+#4035=DIRECTION('ref_axis',(-1.,0.,0.));
+#4036=DIRECTION('center_axis',(0.,-1.,0.));
+#4037=DIRECTION('ref_axis',(-1.,0.,0.));
+#4038=DIRECTION('',(-1.,0.,0.));
+#4039=DIRECTION('',(0.,0.,-1.));
+#4040=DIRECTION('',(-1.,0.,0.));
+#4041=DIRECTION('',(0.,0.,-1.));
+#4042=DIRECTION('center_axis',(1.,2.51096964037364E-16,0.));
+#4043=DIRECTION('ref_axis',(2.51096964037364E-16,-1.,0.));
+#4044=DIRECTION('',(2.51096964037364E-16,-1.,0.));
+#4045=DIRECTION('',(0.,0.,-1.));
+#4046=DIRECTION('',(2.51096964037364E-16,-1.,0.));
+#4047=DIRECTION('center_axis',(0.,1.,0.));
+#4048=DIRECTION('ref_axis',(1.,0.,0.));
+#4049=DIRECTION('',(1.,0.,0.));
+#4050=DIRECTION('',(0.,0.,-1.));
+#4051=DIRECTION('',(1.,0.,0.));
+#4052=DIRECTION('center_axis',(-1.,0.,0.));
+#4053=DIRECTION('ref_axis',(0.,1.,0.));
+#4054=DIRECTION('',(0.,1.,0.));
+#4055=DIRECTION('',(0.,1.,0.));
+#4056=DIRECTION('center_axis',(0.,0.,-1.));
+#4057=DIRECTION('ref_axis',(-1.,0.,0.));
+#4058=DIRECTION('center_axis',(1.,-3.94745964311167E-15,0.));
+#4059=DIRECTION('ref_axis',(-3.94745964311167E-15,-1.,0.));
+#4060=DIRECTION('',(-3.94745964311167E-15,-1.,0.));
+#4061=DIRECTION('',(0.,0.,-1.));
+#4062=DIRECTION('',(-3.94745964311167E-15,-1.,0.));
+#4063=DIRECTION('',(0.,0.,-1.));
+#4064=DIRECTION('center_axis',(0.,1.,0.));
+#4065=DIRECTION('ref_axis',(1.,0.,0.));
+#4066=DIRECTION('',(1.,0.,0.));
+#4067=DIRECTION('',(0.,0.,-1.));
+#4068=DIRECTION('',(1.,0.,0.));
+#4069=DIRECTION('center_axis',(-1.,0.,0.));
+#4070=DIRECTION('ref_axis',(0.,1.,0.));
+#4071=DIRECTION('',(0.,1.,0.));
+#4072=DIRECTION('',(0.,0.,-1.));
+#4073=DIRECTION('',(0.,1.,0.));
+#4074=DIRECTION('center_axis',(-3.55271367880053E-15,-1.,0.));
+#4075=DIRECTION('ref_axis',(-1.,3.55271367880053E-15,0.));
+#4076=DIRECTION('',(-1.,3.55271367880053E-15,0.));
+#4077=DIRECTION('',(-1.,3.55271367880053E-15,0.));
+#4078=DIRECTION('center_axis',(0.,0.,-1.));
+#4079=DIRECTION('ref_axis',(-1.,0.,0.));
+#4080=DIRECTION('center_axis',(1.,1.2989865473931E-16,0.));
+#4081=DIRECTION('ref_axis',(1.2989865473931E-16,-1.,0.));
+#4082=DIRECTION('',(1.2989865473931E-16,-1.,0.));
+#4083=DIRECTION('',(0.,0.,-1.));
+#4084=DIRECTION('',(1.2989865473931E-16,-1.,0.));
+#4085=DIRECTION('',(0.,0.,-1.));
+#4086=DIRECTION('center_axis',(0.,1.,0.));
+#4087=DIRECTION('ref_axis',(1.,0.,0.));
+#4088=DIRECTION('',(1.,0.,0.));
+#4089=DIRECTION('',(0.,0.,-1.));
+#4090=DIRECTION('',(1.,0.,0.));
+#4091=DIRECTION('center_axis',(-1.,-4.93432455388957E-16,0.));
+#4092=DIRECTION('ref_axis',(-4.93432455388957E-16,1.,0.));
+#4093=DIRECTION('',(-4.93432455388957E-16,1.,0.));
+#4094=DIRECTION('',(0.,0.,-1.));
+#4095=DIRECTION('',(-4.93432455388957E-16,1.,0.));
+#4096=DIRECTION('center_axis',(0.,-1.,0.));
+#4097=DIRECTION('ref_axis',(-1.,0.,0.));
+#4098=DIRECTION('',(-1.,0.,0.));
+#4099=DIRECTION('',(-1.,0.,0.));
+#4100=DIRECTION('center_axis',(0.,0.,-1.));
+#4101=DIRECTION('ref_axis',(-1.,0.,0.));
+#4102=DIRECTION('center_axis',(0.,0.,-1.));
+#4103=DIRECTION('ref_axis',(1.,-1.04404194060592E-15,0.));
+#4104=DIRECTION('center_axis',(-4.93038065763132E-31,-4.16333634234434E-16,
+-1.));
+#4105=DIRECTION('ref_axis',(1.,-1.04404194060592E-15,0.));
+#4106=DIRECTION('',(0.,0.,-1.));
+#4107=DIRECTION('center_axis',(3.18099429147958E-31,2.68611088233284E-16,
+1.));
+#4108=DIRECTION('ref_axis',(1.,-1.04404194060592E-15,0.));
+#4109=DIRECTION('center_axis',(3.18099429147958E-31,2.68611088233284E-16,
+1.));
+#4110=DIRECTION('ref_axis',(1.,-1.04404194060592E-15,0.));
+#4111=DIRECTION('center_axis',(0.,0.,-1.));
+#4112=DIRECTION('ref_axis',(1.,-1.04404194060592E-15,0.));
+#4113=DIRECTION('center_axis',(-4.93038065763132E-31,-4.16333634234434E-16,
+-1.));
+#4114=DIRECTION('ref_axis',(1.,-1.04404194060592E-15,0.));
+#4115=DIRECTION('',(0.,0.,-1.));
+#4116=DIRECTION('center_axis',(3.18099429147958E-31,2.68611088233284E-16,
+1.));
+#4117=DIRECTION('ref_axis',(1.,-1.04404194060592E-15,0.));
+#4118=DIRECTION('center_axis',(3.18099429147958E-31,2.68611088233284E-16,
+1.));
+#4119=DIRECTION('ref_axis',(1.,-1.04404194060592E-15,0.));
+#4120=DIRECTION('center_axis',(-3.18099429147958E-31,-2.68611088233284E-16,
+-1.));
+#4121=DIRECTION('ref_axis',(-9.17912793601306E-16,-1.,2.68611088233284E-16));
+#4122=DIRECTION('',(-1.,1.1842378929335E-15,0.));
+#4123=DIRECTION('',(-9.17912793601306E-16,-1.,2.68611088233284E-16));
+#4124=DIRECTION('',(1.,-1.1842378929335E-15,0.));
+#4125=DIRECTION('',(1.,-1.1842378929335E-15,0.));
+#4126=DIRECTION('',(-1.1842378929335E-15,-1.,2.68611088233284E-16));
+#4127=DIRECTION('',(-1.,1.1842378929335E-15,0.));
+#4128=DIRECTION('center_axis',(0.,1.,0.));
+#4129=DIRECTION('ref_axis',(2.83276944882399E-16,0.,-1.));
+#4130=DIRECTION('',(0.,-1.,0.));
+#4131=DIRECTION('center_axis',(0.,-1.,0.));
+#4132=DIRECTION('ref_axis',(1.,0.,0.));
+#4133=DIRECTION('',(0.,1.,0.));
+#4134=DIRECTION('center_axis',(0.,1.,0.));
+#4135=DIRECTION('ref_axis',(1.,0.,0.));
+#4136=DIRECTION('center_axis',(0.,1.,0.));
+#4137=DIRECTION('ref_axis',(-1.83697019872103E-16,0.,-1.));
+#4138=DIRECTION('',(0.,1.,0.));
+#4139=DIRECTION('center_axis',(0.,1.,0.));
+#4140=DIRECTION('ref_axis',(1.,0.,0.));
+#4141=DIRECTION('',(0.,-1.,0.));
+#4142=DIRECTION('center_axis',(0.,-1.,0.));
+#4143=DIRECTION('ref_axis',(1.,0.,0.));
+#4144=DIRECTION('center_axis',(0.,0.,1.));
+#4145=DIRECTION('ref_axis',(1.,0.,0.));
+#4146=DIRECTION('',(-1.,0.,0.));
+#4147=DIRECTION('',(0.,1.,0.));
+#4148=DIRECTION('center_axis',(0.,0.,-1.));
+#4149=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4150=DIRECTION('center_axis',(0.,0.,1.));
+#4151=DIRECTION('ref_axis',(1.,0.,0.));
+#4152=DIRECTION('',(9.17912793601306E-16,1.,0.));
+#4153=DIRECTION('center_axis',(0.,0.,-1.));
+#4154=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4155=DIRECTION('center_axis',(0.,0.,1.));
+#4156=DIRECTION('ref_axis',(1.,0.,0.));
+#4157=DIRECTION('center_axis',(0.,0.,-1.));
+#4158=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4159=DIRECTION('center_axis',(0.,0.,1.));
+#4160=DIRECTION('ref_axis',(0.,1.,0.));
+#4161=DIRECTION('center_axis',(0.,0.,-1.));
+#4162=DIRECTION('ref_axis',(1.,0.,0.));
+#4163=DIRECTION('center_axis',(0.,0.,1.));
+#4164=DIRECTION('ref_axis',(1.,0.,0.));
+#4165=DIRECTION('center_axis',(0.,0.,-1.));
+#4166=DIRECTION('ref_axis',(1.,0.,0.));
+#4167=DIRECTION('',(4.58956396800653E-16,-1.,0.));
+#4168=DIRECTION('center_axis',(0.,0.,1.));
+#4169=DIRECTION('ref_axis',(1.,0.,0.));
+#4170=DIRECTION('center_axis',(0.,0.,-1.));
+#4171=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4172=DIRECTION('',(0.,-1.,0.));
+#4173=DIRECTION('',(-1.,0.,0.));
+#4174=DIRECTION('',(1.,0.,0.));
+#4175=DIRECTION('center_axis',(0.,0.,-1.));
+#4176=DIRECTION('ref_axis',(0.707106781186548,-0.707106781186548,0.));
+#4177=DIRECTION('',(0.,1.,0.));
+#4178=DIRECTION('center_axis',(0.,0.,1.));
+#4179=DIRECTION('ref_axis',(-0.76283740335329,0.646590361856106,0.));
+#4180=DIRECTION('center_axis',(0.,0.,1.));
+#4181=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4182=DIRECTION('center_axis',(0.,0.,1.));
+#4183=DIRECTION('ref_axis',(0.36363636363636,-0.931540978723601,0.));
+#4184=DIRECTION('center_axis',(0.,0.,1.));
+#4185=DIRECTION('ref_axis',(1.,0.,0.));
+#4186=DIRECTION('center_axis',(0.,0.,1.));
+#4187=DIRECTION('ref_axis',(0.36363636363636,-0.931540978723601,0.));
+#4188=DIRECTION('',(-4.58956396800653E-16,1.,0.));
+#4189=DIRECTION('center_axis',(0.,0.,1.));
+#4190=DIRECTION('ref_axis',(1.,0.,0.));
+#4191=DIRECTION('center_axis',(0.,0.,-1.));
+#4192=DIRECTION('ref_axis',(0.,1.,0.));
+#4193=DIRECTION('center_axis',(0.,0.,1.));
+#4194=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4195=DIRECTION('center_axis',(0.,0.,1.));
+#4196=DIRECTION('ref_axis',(1.,0.,0.));
+#4197=DIRECTION('center_axis',(0.,0.,1.));
+#4198=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4199=DIRECTION('',(-9.17912793601306E-16,-1.,0.));
+#4200=DIRECTION('center_axis',(0.,0.,1.));
+#4201=DIRECTION('ref_axis',(-1.,0.,0.));
+#4202=DIRECTION('center_axis',(0.,0.,1.));
+#4203=DIRECTION('ref_axis',(1.,0.,0.));
+#4204=DIRECTION('center_axis',(0.,0.,1.));
+#4205=DIRECTION('ref_axis',(-1.,0.,0.));
+#4206=DIRECTION('center_axis',(0.,0.,1.));
+#4207=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4208=DIRECTION('center_axis',(0.,0.,1.));
+#4209=DIRECTION('ref_axis',(0.7628374033533,0.646590361856094,0.));
+#4210=DIRECTION('',(0.,-1.,0.));
+#4211=DIRECTION('center_axis',(0.,0.,-1.));
+#4212=DIRECTION('ref_axis',(-0.707106781186548,-0.707106781186548,0.));
+#4213=DIRECTION('',(1.,0.,0.));
+#4214=DIRECTION('center_axis',(0.,0.,-1.));
+#4215=DIRECTION('ref_axis',(1.,0.,0.));
+#4216=DIRECTION('center_axis',(0.,0.,-1.));
+#4217=DIRECTION('ref_axis',(1.,0.,0.));
+#4218=DIRECTION('center_axis',(0.,0.,-1.));
+#4219=DIRECTION('ref_axis',(1.,0.,0.));
+#4220=DIRECTION('center_axis',(0.,0.,-1.));
+#4221=DIRECTION('ref_axis',(1.,0.,0.));
+#4222=DIRECTION('center_axis',(0.,-1.,0.));
+#4223=DIRECTION('ref_axis',(1.,0.,0.));
+#4224=DIRECTION('',(0.,0.,1.));
+#4225=DIRECTION('',(-1.,0.,0.));
+#4226=DIRECTION('',(0.,0.,-1.));
+#4227=DIRECTION('',(1.,0.,0.));
+#4228=DIRECTION('center_axis',(0.408248290463862,0.408248290463854,-0.816496580927731));
+#4229=DIRECTION('ref_axis',(-0.577350269189639,-0.577350269189618,-0.577350269189621));
+#4230=DIRECTION('center_axis',(0.,-1.,0.));
+#4231=DIRECTION('ref_axis',(0.,0.,-1.));
+#4232=DIRECTION('center_axis',(-1.,4.93038065763134E-30,1.77635683940025E-14));
+#4233=DIRECTION('ref_axis',(0.,-1.,2.7755575615629E-16));
+#4234=DIRECTION('center_axis',(0.,-4.16333634234435E-16,-1.));
+#4235=DIRECTION('ref_axis',(-1.,0.,0.));
+#4236=DIRECTION('center_axis',(-1.,1.1842378929335E-15,0.));
+#4237=DIRECTION('ref_axis',(0.,-0.707106781186546,-0.707106781186549));
+#4238=DIRECTION('center_axis',(-1.,0.,0.));
+#4239=DIRECTION('ref_axis',(0.,0.,-1.));
+#4240=DIRECTION('',(-1.,1.1842378929335E-15,0.));
+#4241=DIRECTION('center_axis',(2.62953635073671E-31,2.22044604925031E-16,
+1.));
+#4242=DIRECTION('ref_axis',(-0.707106781186541,-0.707106781186554,1.96261557335474E-16));
+#4243=DIRECTION('center_axis',(-4.93038065763132E-31,-4.16333634234434E-16,
+-1.));
+#4244=DIRECTION('ref_axis',(-0.707106781186541,-0.707106781186554,1.96261557335474E-16));
+#4245=DIRECTION('',(-2.62953635073671E-31,-2.22044604925031E-16,-1.));
+#4246=DIRECTION('',(2.62953635073671E-31,2.22044604925031E-16,1.));
+#4247=DIRECTION('center_axis',(-0.40824829046386,-0.816496580927727,-0.408248290463864));
+#4248=DIRECTION('ref_axis',(-0.577350269189624,0.577350269189624,-0.577350269189629));
+#4249=DIRECTION('center_axis',(0.,0.,-1.));
+#4250=DIRECTION('ref_axis',(0.,1.,0.));
+#4251=DIRECTION('center_axis',(-1.,0.,0.));
+#4252=DIRECTION('ref_axis',(0.,0.,-1.));
+#4253=DIRECTION('center_axis',(0.,1.,0.));
+#4254=DIRECTION('ref_axis',(-1.,0.,0.));
+#4255=DIRECTION('center_axis',(-1.,1.1842378929335E-15,0.));
+#4256=DIRECTION('ref_axis',(0.,0.707106781186546,-0.707106781186549));
+#4257=DIRECTION('',(1.,-1.1842378929335E-15,0.));
+#4258=DIRECTION('center_axis',(-1.,0.,0.));
+#4259=DIRECTION('ref_axis',(0.,1.,-1.57873922268515E-9));
+#4260=DIRECTION('center_axis',(-1.1842378929335E-15,-1.,2.68611088233284E-16));
+#4261=DIRECTION('ref_axis',(-0.70710678118654,0.,-0.707106781186555));
+#4262=DIRECTION('',(1.1842378929335E-15,1.,-2.68611088233284E-16));
+#4263=DIRECTION('center_axis',(0.,0.,-1.));
+#4264=DIRECTION('ref_axis',(-0.707106781186541,0.707106781186554,0.));
+#4265=DIRECTION('center_axis',(-4.93038065763132E-31,-4.16333634234434E-16,
+-1.));
+#4266=DIRECTION('ref_axis',(-0.707106781186541,0.707106781186554,0.));
+#4267=DIRECTION('',(0.,0.,-1.));
+#4268=DIRECTION('',(0.,0.,1.));
+#4269=DIRECTION('center_axis',(-1.1842378929335E-15,-1.,2.22044604925031E-16));
+#4270=DIRECTION('ref_axis',(2.03817583610834E-31,2.22044604925031E-16,1.));
+#4271=DIRECTION('center_axis',(-1.1842378929335E-15,-1.,2.22044604925031E-16));
+#4272=DIRECTION('ref_axis',(-0.707106781186548,6.80373398762969E-16,-0.707106781186547));
+#4273=DIRECTION('',(-2.03817583610834E-31,-2.22044604925031E-16,-1.));
+#4274=DIRECTION('',(-1.,1.1842378929335E-15,0.));
+#4275=DIRECTION('center_axis',(1.1842378929335E-15,1.,-2.22044604925031E-16));
+#4276=DIRECTION('ref_axis',(0.,0.,1.));
+#4277=DIRECTION('center_axis',(1.1842378929335E-15,1.,-2.22044604925031E-16));
+#4278=DIRECTION('ref_axis',(-0.707106781186548,6.93889390390723E-16,-0.707106781186547));
+#4279=DIRECTION('center_axis',(0.,-1.38777878078145E-16,-1.));
+#4280=DIRECTION('ref_axis',(0.,1.,-1.38777878078145E-16));
+#4281=DIRECTION('center_axis',(0.,0.,1.));
+#4282=DIRECTION('ref_axis',(1.,0.,0.));
+#4283=DIRECTION('',(-9.17912793601306E-16,-1.,0.));
+#4284=DIRECTION('center_axis',(0.,0.,1.));
+#4285=DIRECTION('ref_axis',(-0.581238193719098,0.813733471206734,0.));
+#4286=DIRECTION('center_axis',(0.,0.,-1.));
+#4287=DIRECTION('ref_axis',(1.01506105108585E-16,-1.,0.));
+#4288=DIRECTION('center_axis',(0.,0.,1.));
+#4289=DIRECTION('ref_axis',(0.581238193719097,0.813733471206735,0.));
+#4290=DIRECTION('',(-4.58956396800653E-16,1.,0.));
+#4291=DIRECTION('center_axis',(0.,0.,1.));
+#4292=DIRECTION('ref_axis',(0.82572282384477,-0.564076074817767,0.));
+#4293=DIRECTION('center_axis',(0.,0.,1.));
+#4294=DIRECTION('ref_axis',(0.260496577422837,-0.96547477085162,0.));
+#4295=DIRECTION('center_axis',(0.,0.,-1.));
+#4296=DIRECTION('ref_axis',(-0.762837403353298,0.646590361856096,0.));
+#4297=DIRECTION('',(0.,1.,0.));
+#4298=DIRECTION('',(1.,0.,0.));
+#4299=DIRECTION('',(0.,-1.,0.));
+#4300=DIRECTION('center_axis',(0.,0.,-1.));
+#4301=DIRECTION('ref_axis',(0.762837403353298,0.646590361856097,0.));
+#4302=DIRECTION('center_axis',(0.,0.,1.));
+#4303=DIRECTION('ref_axis',(-0.260496577422837,-0.96547477085162,0.));
+#4304=DIRECTION('center_axis',(0.,0.,1.));
+#4305=DIRECTION('ref_axis',(-0.82572282384477,-0.564076074817767,0.));
+#4306=DIRECTION('',(-9.17912793601306E-16,-1.,0.));
+#4307=DIRECTION('',(-2.37904933848248E-15,-1.,0.));
+#4308=DIRECTION('',(1.,0.,0.));
+#4309=DIRECTION('',(-4.75809867696496E-16,1.,0.));
+#4310=DIRECTION('',(-1.,0.,0.));
+#4311=DIRECTION('',(-1.,3.22973970800045E-15,0.));
+#4312=DIRECTION('',(-3.17206578464331E-15,-1.,0.));
+#4313=DIRECTION('',(1.,-6.45947941600091E-15,0.));
+#4314=DIRECTION('',(2.22044604925031E-15,1.,0.));
+#4315=DIRECTION('',(-6.3441315692866E-16,1.,0.));
+#4316=DIRECTION('',(-1.,0.,0.));
+#4317=DIRECTION('',(3.1720657846433E-16,-1.,0.));
+#4318=DIRECTION('',(1.,0.,0.));
+#4319=DIRECTION('',(0.,1.,0.));
+#4320=DIRECTION('',(-1.,0.,0.));
+#4321=DIRECTION('',(0.,-1.,0.));
+#4322=DIRECTION('',(1.,-3.22973970800051E-15,0.));
+#4323=DIRECTION('',(0.,-1.,0.));
+#4324=DIRECTION('',(1.,0.,0.));
+#4325=DIRECTION('',(0.,1.,0.));
+#4326=DIRECTION('',(-1.,0.,0.));
+#4327=DIRECTION('center_axis',(9.17912793601306E-16,1.,0.));
+#4328=DIRECTION('ref_axis',(-0.167236724348853,0.,0.985916770335643));
+#4329=DIRECTION('center_axis',(-2.03817583610834E-31,-2.22044604925031E-16,
+-1.));
+#4330=DIRECTION('ref_axis',(0.707106781186541,0.707106781186554,-1.56395928501706E-16));
+#4331=DIRECTION('',(2.03817583610834E-31,2.22044604925031E-16,1.));
+#4332=DIRECTION('center_axis',(4.93038065763132E-31,4.16333634234434E-16,
+1.));
+#4333=DIRECTION('ref_axis',(0.707106781186541,0.707106781186554,-1.56395928501706E-16));
+#4334=DIRECTION('center_axis',(0.,0.,1.));
+#4335=DIRECTION('ref_axis',(0.,1.,0.));
+#4336=DIRECTION('center_axis',(4.93038065763132E-31,4.16333634234434E-16,
+1.));
+#4337=DIRECTION('ref_axis',(0.,1.,0.));
+#4338=DIRECTION('',(0.,0.,-1.));
+#4339=DIRECTION('center_axis',(0.,0.,-1.));
+#4340=DIRECTION('ref_axis',(0.986411214502295,-0.164295209620086,0.));
+#4341=DIRECTION('',(0.,0.,1.));
+#4342=DIRECTION('center_axis',(0.,0.,1.));
+#4343=DIRECTION('ref_axis',(1.,0.,0.));
+#4344=DIRECTION('center_axis',(0.,0.,-1.));
+#4345=DIRECTION('ref_axis',(-0.581238193719098,0.813733471206734,0.));
+#4346=DIRECTION('center_axis',(0.945945945945949,-0.324324324324316,0.));
+#4347=DIRECTION('ref_axis',(0.,0.,-1.));
+#4348=DIRECTION('center_axis',(0.,0.,1.));
+#4349=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4350=DIRECTION('center_axis',(4.93038065763132E-31,4.16333634234434E-16,
+1.));
+#4351=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4352=DIRECTION('',(0.,0.,1.));
+#4353=DIRECTION('',(0.,0.,-1.));
+#4354=DIRECTION('center_axis',(0.,0.,-1.));
+#4355=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4356=DIRECTION('',(0.,0.,1.));
+#4357=DIRECTION('',(0.,0.,1.));
+#4358=DIRECTION('center_axis',(0.,0.,1.));
+#4359=DIRECTION('ref_axis',(1.,0.,0.));
+#4360=DIRECTION('center_axis',(0.,0.,1.));
+#4361=DIRECTION('ref_axis',(0.762837403353298,0.646590361856097,0.));
+#4362=DIRECTION('center_axis',(-0.986486625343149,0.163841807909597,0.));
+#4363=DIRECTION('ref_axis',(0.,0.,-1.));
+#4364=DIRECTION('center_axis',(0.,-1.,0.));
+#4365=DIRECTION('ref_axis',(-1.,0.,0.));
+#4366=DIRECTION('center_axis',(-9.17912793601306E-16,-1.,0.));
+#4367=DIRECTION('ref_axis',(-0.70710678118654,0.,-0.707106781186555));
+#4368=DIRECTION('center_axis',(0.,1.,0.));
+#4369=DIRECTION('ref_axis',(0.,0.,-1.));
+#4370=DIRECTION('',(9.17912793601306E-16,1.,0.));
+#4371=DIRECTION('center_axis',(0.,0.,1.));
+#4372=DIRECTION('ref_axis',(1.,0.,0.));
+#4373=DIRECTION('center_axis',(-0.931540978723597,0.363636363636372,0.));
+#4374=DIRECTION('ref_axis',(0.,0.,-1.));
+#4375=DIRECTION('center_axis',(0.,0.,-1.));
+#4376=DIRECTION('ref_axis',(-0.82572282384477,-0.564076074817767,0.));
+#4377=DIRECTION('center_axis',(0.,0.,1.));
+#4378=DIRECTION('ref_axis',(1.,0.,0.));
+#4379=DIRECTION('center_axis',(0.,0.,-1.));
+#4380=DIRECTION('ref_axis',(-0.260496577422837,-0.96547477085162,0.));
+#4381=DIRECTION('center_axis',(0.408248290463861,0.408248290463861,-0.816496580927728));
+#4382=DIRECTION('ref_axis',(-0.577350269189625,-0.577350269189625,-0.577350269189628));
+#4383=DIRECTION('center_axis',(0.,0.,-1.));
+#4384=DIRECTION('ref_axis',(-1.,0.,0.));
+#4385=DIRECTION('center_axis',(0.,-1.,0.));
+#4386=DIRECTION('ref_axis',(0.,0.,-1.));
+#4387=DIRECTION('center_axis',(-1.,0.,-8.88178419700125E-15));
+#4388=DIRECTION('ref_axis',(0.,-1.,0.));
+#4389=DIRECTION('center_axis',(0.,-1.,0.));
+#4390=DIRECTION('ref_axis',(-0.707106781186553,0.,-0.707106781186543));
+#4391=DIRECTION('',(0.,1.,0.));
+#4392=DIRECTION('center_axis',(-0.408248290463858,-0.81649658092773,0.408248290463861));
+#4393=DIRECTION('ref_axis',(0.577350269189624,-0.577350269189624,-0.577350269189629));
+#4394=DIRECTION('center_axis',(0.,0.,-1.));
+#4395=DIRECTION('ref_axis',(0.,-1.,0.));
+#4396=DIRECTION('center_axis',(1.,0.,0.));
+#4397=DIRECTION('ref_axis',(0.,0.,-1.));
+#4398=DIRECTION('center_axis',(0.,-1.,0.));
+#4399=DIRECTION('ref_axis',(1.,0.,0.));
+#4400=DIRECTION('center_axis',(1.,0.,0.));
+#4401=DIRECTION('ref_axis',(0.,-0.707106781186546,-0.707106781186549));
+#4402=DIRECTION('center_axis',(0.,0.,1.));
+#4403=DIRECTION('ref_axis',(1.,0.,0.));
+#4404=DIRECTION('center_axis',(0.,0.,1.));
+#4405=DIRECTION('ref_axis',(-0.762837403353298,0.646590361856096,0.));
+#4406=DIRECTION('center_axis',(0.,-1.,0.));
+#4407=DIRECTION('ref_axis',(0.,0.,-1.));
+#4408=DIRECTION('center_axis',(0.986486625343148,0.163841807909606,0.));
+#4409=DIRECTION('ref_axis',(0.163841807909606,-0.986486625343148,0.));
+#4410=DIRECTION('center_axis',(0.,1.,0.));
+#4411=DIRECTION('ref_axis',(0.707106781186546,0.,-0.707106781186549));
+#4412=DIRECTION('',(0.,-1.,0.));
+#4413=DIRECTION('center_axis',(0.,0.,1.));
+#4414=DIRECTION('ref_axis',(1.,0.,0.));
+#4415=DIRECTION('center_axis',(-0.931540978723602,-0.363636363636359,0.));
+#4416=DIRECTION('ref_axis',(0.,0.,-1.));
+#4417=DIRECTION('center_axis',(0.,0.,-1.));
+#4418=DIRECTION('ref_axis',(0.260496577422838,-0.96547477085162,0.));
+#4419=DIRECTION('center_axis',(0.,0.,1.));
+#4420=DIRECTION('ref_axis',(1.,0.,0.));
+#4421=DIRECTION('center_axis',(0.,-1.,0.));
+#4422=DIRECTION('ref_axis',(0.,0.,-1.));
+#4423=DIRECTION('center_axis',(0.,0.,-1.));
+#4424=DIRECTION('ref_axis',(0.82572282384477,-0.564076074817767,0.));
+#4425=DIRECTION('center_axis',(-4.58956396800653E-16,1.,0.));
+#4426=DIRECTION('ref_axis',(0.707106781186549,0.,-0.707106781186546));
+#4427=DIRECTION('center_axis',(0.,-1.,0.));
+#4428=DIRECTION('ref_axis',(0.,0.,-1.));
+#4429=DIRECTION('',(4.58956396800653E-16,-1.,0.));
+#4430=DIRECTION('center_axis',(0.,0.,1.));
+#4431=DIRECTION('ref_axis',(1.,0.,0.));
+#4432=DIRECTION('center_axis',(0.945945945945946,0.324324324324324,0.));
+#4433=DIRECTION('ref_axis',(0.,0.,-1.));
+#4434=DIRECTION('center_axis',(0.,0.,-1.));
+#4435=DIRECTION('ref_axis',(0.581238193719097,0.813733471206734,0.));
+#4436=DIRECTION('center_axis',(0.,0.,-1.));
+#4437=DIRECTION('ref_axis',(-1.,0.,0.));
+#4438=DIRECTION('center_axis',(0.,0.,1.));
+#4439=DIRECTION('ref_axis',(1.01506105108585E-16,-1.,0.));
+#4440=DIRECTION('center_axis',(0.,0.,1.));
+#4441=DIRECTION('ref_axis',(-0.76283740335329,0.646590361856106,0.));
+#4442=DIRECTION('',(0.,0.,-1.));
+#4443=DIRECTION('',(0.,0.,1.));
+#4444=DIRECTION('center_axis',(0.,0.,1.));
+#4445=DIRECTION('ref_axis',(0.707106781186548,-0.707106781186548,0.));
+#4446=DIRECTION('',(0.,0.,1.));
+#4447=DIRECTION('center_axis',(0.,0.,1.));
+#4448=DIRECTION('ref_axis',(-0.707106781186548,-0.707106781186548,0.));
+#4449=DIRECTION('',(0.,0.,-1.));
+#4450=DIRECTION('center_axis',(0.,0.,1.));
+#4451=DIRECTION('ref_axis',(0.7628374033533,0.646590361856094,0.));
+#4452=DIRECTION('',(0.,0.,-1.));
+#4453=DIRECTION('',(0.,0.,1.));
+#4454=DIRECTION('center_axis',(0.,0.,1.));
+#4455=DIRECTION('ref_axis',(-1.,0.,0.));
+#4456=DIRECTION('',(0.,0.,1.));
+#4457=DIRECTION('',(0.,0.,-1.));
+#4458=DIRECTION('center_axis',(0.,0.,-1.));
+#4459=DIRECTION('ref_axis',(-1.,0.,0.));
+#4460=DIRECTION('',(0.,0.,1.));
+#4461=DIRECTION('',(0.,0.,1.));
+#4462=DIRECTION('center_axis',(0.,0.,1.));
+#4463=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4464=DIRECTION('center_axis',(1.1842378929335E-15,1.,0.));
+#4465=DIRECTION('ref_axis',(0.,0.,-1.));
+#4466=DIRECTION('',(-1.,1.1842378929335E-15,0.));
+#4467=DIRECTION('center_axis',(4.93038065763132E-31,4.16333634234434E-16,
+1.));
+#4468=DIRECTION('ref_axis',(9.17912793601306E-16,1.,-4.16333634234434E-16));
+#4469=DIRECTION('',(-9.17912793601306E-16,-1.,4.16333634234434E-16));
+#4470=DIRECTION('',(9.17912793601306E-16,1.,-4.16333634234434E-16));
+#4471=DIRECTION('center_axis',(-1.,1.1842378929335E-15,0.));
+#4472=DIRECTION('ref_axis',(0.,0.,1.));
+#4473=DIRECTION('center_axis',(0.,0.,-1.));
+#4474=DIRECTION('ref_axis',(1.,0.,0.));
+#4475=DIRECTION('center_axis',(0.,0.,-1.));
+#4476=DIRECTION('ref_axis',(1.,0.,0.));
+#4477=DIRECTION('',(0.,0.,-1.));
+#4478=DIRECTION('center_axis',(0.,0.,-1.));
+#4479=DIRECTION('ref_axis',(1.,0.,0.));
+#4480=DIRECTION('center_axis',(0.,0.,1.));
+#4481=DIRECTION('ref_axis',(1.,0.,0.));
+#4482=DIRECTION('center_axis',(0.,0.,-1.));
+#4483=DIRECTION('ref_axis',(1.,0.,0.));
+#4484=DIRECTION('',(0.,0.,-1.));
+#4485=DIRECTION('center_axis',(0.,0.,-1.));
+#4486=DIRECTION('ref_axis',(1.,0.,0.));
+#4487=DIRECTION('center_axis',(0.,0.,1.));
+#4488=DIRECTION('ref_axis',(1.,0.,0.));
+#4489=DIRECTION('center_axis',(0.,0.,-1.));
+#4490=DIRECTION('ref_axis',(1.,0.,0.));
+#4491=DIRECTION('center_axis',(0.,0.,-1.));
+#4492=DIRECTION('ref_axis',(1.,0.,0.));
+#4493=DIRECTION('',(0.,0.,-1.));
+#4494=DIRECTION('center_axis',(0.,0.,-1.));
+#4495=DIRECTION('ref_axis',(1.,0.,0.));
+#4496=DIRECTION('center_axis',(0.,0.,1.));
+#4497=DIRECTION('ref_axis',(1.,0.,0.));
+#4498=DIRECTION('center_axis',(0.,0.,-1.));
+#4499=DIRECTION('ref_axis',(1.,0.,0.));
+#4500=DIRECTION('center_axis',(0.,0.,-1.));
+#4501=DIRECTION('ref_axis',(1.,0.,0.));
+#4502=DIRECTION('',(0.,0.,-1.));
+#4503=DIRECTION('center_axis',(0.,0.,-1.));
+#4504=DIRECTION('ref_axis',(1.,0.,0.));
+#4505=DIRECTION('center_axis',(0.,0.,1.));
+#4506=DIRECTION('ref_axis',(1.,0.,0.));
+#4507=DIRECTION('center_axis',(-0.00013928500099641,0.99999999029835,-1.72852223301933E-6));
+#4508=DIRECTION('ref_axis',(0.857319355398015,0.000120301545608233,0.514784914685222));
+#4509=DIRECTION('center_axis',(0.,0.,1.));
+#4510=DIRECTION('ref_axis',(1.,0.,0.));
+#4511=DIRECTION('',(0.,0.,-1.));
+#4512=DIRECTION('center_axis',(0.,0.,-1.));
+#4513=DIRECTION('ref_axis',(1.,0.,0.));
+#4514=DIRECTION('center_axis',(0.,0.,1.));
+#4515=DIRECTION('ref_axis',(1.,0.,0.));
+#4516=DIRECTION('',(0.,0.,-1.));
+#4517=DIRECTION('center_axis',(0.,0.,1.));
+#4518=DIRECTION('ref_axis',(1.,0.,0.));
+#4519=DIRECTION('center_axis',(0.,0.,1.));
+#4520=DIRECTION('ref_axis',(1.,0.,0.));
+#4521=DIRECTION('center_axis',(0.,0.,1.));
+#4522=DIRECTION('ref_axis',(1.,0.,0.));
+#4523=DIRECTION('center_axis',(0.,-1.,0.));
+#4524=DIRECTION('ref_axis',(-1.,0.,0.));
+#4525=DIRECTION('center_axis',(0.,0.,-1.));
+#4526=DIRECTION('ref_axis',(1.,0.,0.));
+#4527=DIRECTION('center_axis',(0.,0.,-1.));
+#4528=DIRECTION('ref_axis',(1.,0.,0.));
+#4529=DIRECTION('center_axis',(0.,-1.,0.));
+#4530=DIRECTION('ref_axis',(-1.,0.,0.));
+#4531=DIRECTION('center_axis',(0.,0.,1.));
+#4532=DIRECTION('ref_axis',(1.,0.,0.));
+#4533=DIRECTION('',(0.,0.,-1.));
+#4534=DIRECTION('center_axis',(0.,0.,-1.));
+#4535=DIRECTION('ref_axis',(1.,0.,0.));
+#4536=DIRECTION('center_axis',(0.,0.,1.));
+#4537=DIRECTION('ref_axis',(1.,0.,0.));
+#4538=DIRECTION('center_axis',(0.,0.,1.));
+#4539=DIRECTION('ref_axis',(1.,0.,0.));
+#4540=DIRECTION('',(0.,0.,-1.));
+#4541=DIRECTION('center_axis',(-0.246233704377792,0.968635005774422,-0.0333944369135777));
+#4542=DIRECTION('ref_axis',(0.860998330628074,0.234432601747609,0.451357097976222));
+#4543=DIRECTION('center_axis',(0.,0.,1.));
+#4544=DIRECTION('ref_axis',(1.,0.,0.));
+#4545=DIRECTION('',(0.,0.,-1.));
+#4546=DIRECTION('center_axis',(0.,0.,-1.));
+#4547=DIRECTION('ref_axis',(1.,0.,0.));
+#4548=DIRECTION('center_axis',(0.,0.,1.));
+#4549=DIRECTION('ref_axis',(1.,0.,0.));
+#4550=DIRECTION('center_axis',(0.,0.,1.));
+#4551=DIRECTION('ref_axis',(1.,0.,0.));
+#4552=DIRECTION('',(0.,0.,-1.));
+#4553=DIRECTION('center_axis',(0.,0.,1.));
+#4554=DIRECTION('ref_axis',(0.,1.,0.));
+#4555=DIRECTION('center_axis',(0.,0.,1.));
+#4556=DIRECTION('ref_axis',(1.,0.,0.));
+#4557=DIRECTION('center_axis',(0.,0.,1.));
+#4558=DIRECTION('ref_axis',(-1.83697019872103E-16,1.,0.));
+#4559=DIRECTION('center_axis',(0.,0.,-1.));
+#4560=DIRECTION('ref_axis',(1.,0.,0.));
+#4561=DIRECTION('center_axis',(0.,0.,1.));
+#4562=DIRECTION('ref_axis',(1.,0.,0.));
+#4563=DIRECTION('center_axis',(0.,0.,1.));
+#4564=DIRECTION('ref_axis',(1.,0.,0.));
+#4565=DIRECTION('center_axis',(0.,0.,1.));
+#4566=DIRECTION('ref_axis',(1.,0.,0.));
+#4567=DIRECTION('center_axis',(0.,0.,-1.));
+#4568=DIRECTION('ref_axis',(1.,0.,0.));
+#4569=DIRECTION('',(0.,0.,-1.));
+#4570=DIRECTION('center_axis',(0.,0.,-1.));
+#4571=DIRECTION('ref_axis',(1.,0.,0.));
+#4572=DIRECTION('center_axis',(0.,0.,1.));
+#4573=DIRECTION('ref_axis',(1.,0.,0.));
+#4574=DIRECTION('center_axis',(0.,0.,-1.));
+#4575=DIRECTION('ref_axis',(1.,0.,0.));
+#4576=DIRECTION('',(0.,0.,-1.));
+#4577=DIRECTION('center_axis',(0.,0.,-1.));
+#4578=DIRECTION('ref_axis',(1.,0.,0.));
+#4579=DIRECTION('center_axis',(0.,0.,1.));
+#4580=DIRECTION('ref_axis',(1.,0.,0.));
+#4581=DIRECTION('center_axis',(0.,0.,-1.));
+#4582=DIRECTION('ref_axis',(1.,0.,0.));
+#4583=DIRECTION('',(0.,0.,-1.));
+#4584=DIRECTION('center_axis',(0.,0.,-1.));
+#4585=DIRECTION('ref_axis',(1.,0.,0.));
+#4586=DIRECTION('center_axis',(0.,0.,1.));
+#4587=DIRECTION('ref_axis',(1.,0.,0.));
+#4588=DIRECTION('center_axis',(0.,0.,-1.));
+#4589=DIRECTION('ref_axis',(1.,0.,0.));
+#4590=DIRECTION('',(0.,0.,-1.));
+#4591=DIRECTION('center_axis',(0.,0.,-1.));
+#4592=DIRECTION('ref_axis',(1.,0.,0.));
+#4593=DIRECTION('center_axis',(0.,0.,1.));
+#4594=DIRECTION('ref_axis',(1.,0.,0.));
+#4595=DIRECTION('center_axis',(1.,4.75809867696496E-16,0.));
+#4596=DIRECTION('ref_axis',(4.75809867696496E-16,-1.,0.));
+#4597=DIRECTION('',(0.,0.,-1.));
+#4598=DIRECTION('',(4.75809867696496E-16,-1.,0.));
+#4599=DIRECTION('',(0.,0.,-1.));
+#4600=DIRECTION('center_axis',(0.,1.,0.));
+#4601=DIRECTION('ref_axis',(1.,0.,0.));
+#4602=DIRECTION('',(1.,0.,0.));
+#4603=DIRECTION('',(0.,0.,-1.));
+#4604=DIRECTION('center_axis',(-1.,2.37904933848248E-15,0.));
+#4605=DIRECTION('ref_axis',(2.37904933848248E-15,1.,0.));
+#4606=DIRECTION('',(2.37904933848248E-15,1.,0.));
+#4607=DIRECTION('',(0.,0.,-1.));
+#4608=DIRECTION('center_axis',(0.,-1.,0.));
+#4609=DIRECTION('ref_axis',(-1.,0.,0.));
+#4610=DIRECTION('',(-1.,0.,0.));
+#4611=DIRECTION('center_axis',(-6.45947941600091E-15,-1.,0.));
+#4612=DIRECTION('ref_axis',(-1.,6.45947941600091E-15,0.));
+#4613=DIRECTION('',(0.,0.,-1.));
+#4614=DIRECTION('',(-1.,6.45947941600091E-15,0.));
+#4615=DIRECTION('',(0.,0.,-1.));
+#4616=DIRECTION('center_axis',(1.,-2.22044604925031E-15,0.));
+#4617=DIRECTION('ref_axis',(-2.22044604925031E-15,-1.,0.));
+#4618=DIRECTION('',(-2.22044604925031E-15,-1.,0.));
+#4619=DIRECTION('',(0.,0.,-1.));
+#4620=DIRECTION('center_axis',(3.22973970800045E-15,1.,0.));
+#4621=DIRECTION('ref_axis',(1.,-3.22973970800045E-15,0.));
+#4622=DIRECTION('',(1.,-3.22973970800045E-15,0.));
+#4623=DIRECTION('',(0.,0.,-1.));
+#4624=DIRECTION('center_axis',(-1.,3.17206578464331E-15,0.));
+#4625=DIRECTION('ref_axis',(3.17206578464331E-15,1.,0.));
+#4626=DIRECTION('',(3.17206578464331E-15,1.,0.));
+#4627=DIRECTION('center_axis',(-1.,-3.1720657846433E-16,0.));
+#4628=DIRECTION('ref_axis',(-3.1720657846433E-16,1.,0.));
+#4629=DIRECTION('',(0.,0.,-1.));
+#4630=DIRECTION('',(-3.1720657846433E-16,1.,0.));
+#4631=DIRECTION('',(0.,0.,-1.));
+#4632=DIRECTION('center_axis',(0.,-1.,0.));
+#4633=DIRECTION('ref_axis',(-1.,0.,0.));
+#4634=DIRECTION('',(-1.,0.,0.));
+#4635=DIRECTION('',(0.,0.,-1.));
+#4636=DIRECTION('center_axis',(1.,6.3441315692866E-16,0.));
+#4637=DIRECTION('ref_axis',(6.3441315692866E-16,-1.,0.));
+#4638=DIRECTION('',(6.3441315692866E-16,-1.,0.));
+#4639=DIRECTION('',(0.,0.,-1.));
+#4640=DIRECTION('center_axis',(0.,1.,0.));
+#4641=DIRECTION('ref_axis',(1.,0.,0.));
+#4642=DIRECTION('',(1.,0.,0.));
+#4643=DIRECTION('center_axis',(-1.,0.,0.));
+#4644=DIRECTION('ref_axis',(0.,1.,0.));
+#4645=DIRECTION('',(0.,0.,-1.));
+#4646=DIRECTION('',(0.,1.,0.));
+#4647=DIRECTION('',(0.,0.,-1.));
+#4648=DIRECTION('center_axis',(-3.22973970800051E-15,-1.,0.));
+#4649=DIRECTION('ref_axis',(-1.,3.22973970800051E-15,0.));
+#4650=DIRECTION('',(-1.,3.22973970800051E-15,0.));
+#4651=DIRECTION('',(0.,0.,-1.));
+#4652=DIRECTION('center_axis',(1.,0.,0.));
+#4653=DIRECTION('ref_axis',(0.,-1.,0.));
+#4654=DIRECTION('',(0.,-1.,0.));
+#4655=DIRECTION('',(0.,0.,-1.));
+#4656=DIRECTION('center_axis',(0.,1.,0.));
+#4657=DIRECTION('ref_axis',(1.,0.,0.));
+#4658=DIRECTION('',(1.,0.,0.));
+#4659=DIRECTION('center_axis',(1.,0.,0.));
+#4660=DIRECTION('ref_axis',(0.,-1.,0.));
+#4661=DIRECTION('',(0.,0.,-1.));
+#4662=DIRECTION('',(0.,-1.,0.));
+#4663=DIRECTION('',(0.,0.,-1.));
+#4664=DIRECTION('center_axis',(0.,1.,0.));
+#4665=DIRECTION('ref_axis',(1.,0.,0.));
+#4666=DIRECTION('',(1.,0.,0.));
+#4667=DIRECTION('',(0.,0.,-1.));
+#4668=DIRECTION('center_axis',(-1.,0.,0.));
+#4669=DIRECTION('ref_axis',(0.,1.,0.));
+#4670=DIRECTION('',(0.,1.,0.));
+#4671=DIRECTION('',(0.,0.,-1.));
+#4672=DIRECTION('center_axis',(0.,-1.,0.));
+#4673=DIRECTION('ref_axis',(-1.,0.,0.));
+#4674=DIRECTION('',(-1.,0.,0.));
+#4675=DIRECTION('center_axis',(1.,-1.66533453693774E-15,0.));
+#4676=DIRECTION('ref_axis',(-1.66533453693774E-15,-1.,0.));
+#4677=DIRECTION('',(-1.66533453693774E-15,-1.,0.));
+#4678=DIRECTION('',(0.,0.,-1.));
+#4679=DIRECTION('',(-1.66533453693774E-15,-1.,0.));
+#4680=DIRECTION('',(0.,0.,-1.));
+#4681=DIRECTION('center_axis',(1.77635683940025E-15,1.,0.));
+#4682=DIRECTION('ref_axis',(1.,-1.77635683940025E-15,0.));
+#4683=DIRECTION('',(1.,-1.77635683940025E-15,0.));
+#4684=DIRECTION('',(0.,0.,-1.));
+#4685=DIRECTION('',(1.,-1.77635683940025E-15,0.));
+#4686=DIRECTION('center_axis',(-1.,0.,0.));
+#4687=DIRECTION('ref_axis',(0.,1.,0.));
+#4688=DIRECTION('',(0.,1.,0.));
+#4689=DIRECTION('',(0.,0.,-1.));
+#4690=DIRECTION('',(0.,1.,0.));
+#4691=DIRECTION('center_axis',(-1.77635683940025E-15,-1.,0.));
+#4692=DIRECTION('ref_axis',(-1.,1.77635683940025E-15,0.));
+#4693=DIRECTION('',(-1.,1.77635683940025E-15,0.));
+#4694=DIRECTION('',(-1.,1.77635683940025E-15,0.));
+#4695=DIRECTION('center_axis',(0.,0.,-1.));
+#4696=DIRECTION('ref_axis',(-1.,0.,0.));
+#4697=DIRECTION('center_axis',(3.5527136788005E-15,1.,0.));
+#4698=DIRECTION('ref_axis',(1.,-3.5527136788005E-15,0.));
+#4699=DIRECTION('',(1.,-3.5527136788005E-15,0.));
+#4700=DIRECTION('',(0.,0.,-1.));
+#4701=DIRECTION('',(1.,-3.5527136788005E-15,0.));
+#4702=DIRECTION('',(0.,0.,-1.));
+#4703=DIRECTION('center_axis',(-1.,4.44089209850064E-15,0.));
+#4704=DIRECTION('ref_axis',(4.44089209850064E-15,1.,0.));
+#4705=DIRECTION('',(4.44089209850064E-15,1.,0.));
+#4706=DIRECTION('',(0.,0.,-1.));
+#4707=DIRECTION('',(4.44089209850064E-15,1.,0.));
+#4708=DIRECTION('center_axis',(0.,-1.,0.));
+#4709=DIRECTION('ref_axis',(-1.,0.,0.));
+#4710=DIRECTION('',(-1.,0.,0.));
+#4711=DIRECTION('',(0.,0.,-1.));
+#4712=DIRECTION('',(-1.,0.,0.));
+#4713=DIRECTION('center_axis',(1.,0.,0.));
+#4714=DIRECTION('ref_axis',(0.,-1.,0.));
+#4715=DIRECTION('',(0.,-1.,0.));
+#4716=DIRECTION('',(0.,-1.,0.));
+#4717=DIRECTION('center_axis',(0.,0.,-1.));
+#4718=DIRECTION('ref_axis',(-1.,0.,0.));
+#4719=DIRECTION('center_axis',(-1.,0.,0.));
+#4720=DIRECTION('ref_axis',(0.,1.,0.));
+#4721=DIRECTION('',(0.,1.,0.));
+#4722=DIRECTION('',(0.,0.,-1.));
+#4723=DIRECTION('',(0.,1.,0.));
+#4724=DIRECTION('',(0.,0.,-1.));
+#4725=DIRECTION('center_axis',(0.,-1.,0.));
+#4726=DIRECTION('ref_axis',(-1.,0.,0.));
+#4727=DIRECTION('',(-1.,0.,0.));
+#4728=DIRECTION('',(0.,0.,-1.));
+#4729=DIRECTION('',(-1.,0.,0.));
+#4730=DIRECTION('center_axis',(1.,0.,0.));
+#4731=DIRECTION('ref_axis',(0.,-1.,0.));
+#4732=DIRECTION('',(0.,-1.,0.));
+#4733=DIRECTION('',(0.,0.,-1.));
+#4734=DIRECTION('',(0.,-1.,0.));
+#4735=DIRECTION('center_axis',(0.,1.,0.));
+#4736=DIRECTION('ref_axis',(1.,0.,0.));
+#4737=DIRECTION('',(1.,0.,0.));
+#4738=DIRECTION('',(1.,0.,0.));
+#4739=DIRECTION('center_axis',(0.,0.,-1.));
+#4740=DIRECTION('ref_axis',(-1.,0.,0.));
+#4741=DIRECTION('center_axis',(-1.,0.,0.));
+#4742=DIRECTION('ref_axis',(0.,1.,0.));
+#4743=DIRECTION('',(0.,1.,0.));
+#4744=DIRECTION('',(0.,0.,-1.));
+#4745=DIRECTION('',(0.,1.,0.));
+#4746=DIRECTION('',(0.,0.,-1.));
+#4747=DIRECTION('center_axis',(-4.61852778244063E-14,-1.,0.));
+#4748=DIRECTION('ref_axis',(-1.,4.61852778244063E-14,0.));
+#4749=DIRECTION('',(-1.,4.61852778244063E-14,0.));
+#4750=DIRECTION('',(0.,0.,-1.));
+#4751=DIRECTION('',(-1.,4.61852778244063E-14,0.));
+#4752=DIRECTION('center_axis',(1.,0.,0.));
+#4753=DIRECTION('ref_axis',(0.,-1.,0.));
+#4754=DIRECTION('',(0.,-1.,0.));
+#4755=DIRECTION('',(0.,0.,-1.));
+#4756=DIRECTION('',(0.,-1.,0.));
+#4757=DIRECTION('center_axis',(0.,1.,0.));
+#4758=DIRECTION('ref_axis',(1.,0.,0.));
+#4759=DIRECTION('',(1.,0.,0.));
+#4760=DIRECTION('',(1.,0.,0.));
+#4761=DIRECTION('center_axis',(0.,0.,-1.));
+#4762=DIRECTION('ref_axis',(-1.,0.,0.));
+#4763=DIRECTION('center_axis',(-1.,0.,0.));
+#4764=DIRECTION('ref_axis',(0.,1.,0.));
+#4765=DIRECTION('',(0.,1.,0.));
+#4766=DIRECTION('',(0.,0.,-1.));
+#4767=DIRECTION('',(0.,1.,0.));
+#4768=DIRECTION('',(0.,0.,-1.));
+#4769=DIRECTION('center_axis',(0.,-1.,0.));
+#4770=DIRECTION('ref_axis',(-1.,0.,0.));
+#4771=DIRECTION('',(-1.,0.,0.));
+#4772=DIRECTION('',(0.,0.,-1.));
+#4773=DIRECTION('',(-1.,0.,0.));
+#4774=DIRECTION('center_axis',(1.,0.,0.));
+#4775=DIRECTION('ref_axis',(0.,-1.,0.));
+#4776=DIRECTION('',(0.,-1.,0.));
+#4777=DIRECTION('',(0.,0.,-1.));
+#4778=DIRECTION('',(0.,-1.,0.));
+#4779=DIRECTION('center_axis',(0.,1.,0.));
+#4780=DIRECTION('ref_axis',(1.,0.,0.));
+#4781=DIRECTION('',(1.,0.,0.));
+#4782=DIRECTION('',(1.,0.,0.));
+#4783=DIRECTION('center_axis',(0.,0.,-1.));
+#4784=DIRECTION('ref_axis',(-1.,0.,0.));
+#4785=DIRECTION('center_axis',(0.,0.,1.));
+#4786=DIRECTION('ref_axis',(1.,0.,0.));
+#4787=DIRECTION('center_axis',(0.,0.,1.));
+#4788=DIRECTION('ref_axis',(1.,0.,0.));
+#4789=DIRECTION('',(0.,0.,-1.));
+#4790=DIRECTION('center_axis',(0.,0.,-1.));
+#4791=DIRECTION('ref_axis',(1.,0.,0.));
+#4792=DIRECTION('center_axis',(0.,0.,1.));
+#4793=DIRECTION('ref_axis',(1.,0.,0.));
+#4794=DIRECTION('center_axis',(0.,0.,1.));
+#4795=DIRECTION('ref_axis',(1.,0.,0.));
+#4796=DIRECTION('center_axis',(0.,0.,1.));
+#4797=DIRECTION('ref_axis',(1.,0.,0.));
+#4798=DIRECTION('',(0.,0.,-1.));
+#4799=DIRECTION('center_axis',(0.,0.,-1.));
+#4800=DIRECTION('ref_axis',(1.,0.,0.));
+#4801=DIRECTION('center_axis',(0.,0.,1.));
+#4802=DIRECTION('ref_axis',(1.,0.,0.));
+#4803=DIRECTION('center_axis',(0.,0.,1.));
+#4804=DIRECTION('ref_axis',(1.,0.,0.));
+#4805=DIRECTION('center_axis',(0.,0.,1.));
+#4806=DIRECTION('ref_axis',(1.,0.,0.));
+#4807=DIRECTION('',(0.,0.,-1.));
+#4808=DIRECTION('center_axis',(0.,0.,-1.));
+#4809=DIRECTION('ref_axis',(1.,0.,0.));
+#4810=DIRECTION('center_axis',(0.,0.,1.));
+#4811=DIRECTION('ref_axis',(1.,0.,0.));
+#4812=DIRECTION('center_axis',(0.,0.,1.));
+#4813=DIRECTION('ref_axis',(1.,0.,0.));
+#4814=DIRECTION('center_axis',(0.,0.,1.));
+#4815=DIRECTION('ref_axis',(1.,0.,0.));
+#4816=DIRECTION('',(0.,0.,-1.));
+#4817=DIRECTION('center_axis',(0.,0.,-1.));
+#4818=DIRECTION('ref_axis',(1.,0.,0.));
+#4819=DIRECTION('center_axis',(0.,0.,1.));
+#4820=DIRECTION('ref_axis',(1.,0.,0.));
+#4821=DIRECTION('center_axis',(0.,0.,1.));
+#4822=DIRECTION('ref_axis',(1.,0.,0.));
+#4823=DIRECTION('center_axis',(0.,0.,1.));
+#4824=DIRECTION('ref_axis',(1.,0.,0.));
+#4825=DIRECTION('',(0.,0.,-1.));
+#4826=DIRECTION('center_axis',(0.,0.,-1.));
+#4827=DIRECTION('ref_axis',(1.,0.,0.));
+#4828=DIRECTION('center_axis',(0.,0.,1.));
+#4829=DIRECTION('ref_axis',(1.,0.,0.));
+#4830=DIRECTION('center_axis',(0.,0.,1.));
+#4831=DIRECTION('ref_axis',(1.,0.,0.));
+#4832=DIRECTION('',(0.,0.,-1.));
+#4833=DIRECTION('',(0.,0.,1.));
+#4834=DIRECTION('center_axis',(0.,0.,-1.));
+#4835=DIRECTION('ref_axis',(1.,0.,0.));
+#4836=DIRECTION('center_axis',(0.,0.,1.));
+#4837=DIRECTION('ref_axis',(1.,0.,0.));
+#4838=DIRECTION('center_axis',(0.,0.,1.));
+#4839=DIRECTION('ref_axis',(-0.662596348126473,-0.748976688188265,0.));
+#4840=DIRECTION('',(0.,0.,1.));
+#4841=DIRECTION('center_axis',(0.,0.,-1.));
+#4842=DIRECTION('ref_axis',(1.,0.,0.));
+#4843=DIRECTION('',(0.,0.,-1.));
+#4844=DIRECTION('center_axis',(0.,0.,1.));
+#4845=DIRECTION('ref_axis',(1.,0.,0.));
+#4846=DIRECTION('center_axis',(0.,0.,1.));
+#4847=DIRECTION('ref_axis',(1.,0.,0.));
+#4848=DIRECTION('center_axis',(0.,0.,1.));
+#4849=DIRECTION('ref_axis',(1.,0.,0.));
+#4850=DIRECTION('center_axis',(0.,0.,1.));
+#4851=DIRECTION('ref_axis',(1.,0.,0.));
+#4852=DIRECTION('',(0.,0.,1.));
+#4853=DIRECTION('center_axis',(0.,0.,-1.));
+#4854=DIRECTION('ref_axis',(1.,0.,0.));
+#4855=DIRECTION('',(0.,0.,-1.));
+#4856=DIRECTION('center_axis',(0.,0.,1.));
+#4857=DIRECTION('ref_axis',(1.,0.,0.));
+#4858=DIRECTION('',(0.,0.,-1.));
+#4859=DIRECTION('',(0.,0.,1.));
+#4860=DIRECTION('center_axis',(0.,0.,-1.));
+#4861=DIRECTION('ref_axis',(0.36363636363636,-0.931540978723601,0.));
+#4862=DIRECTION('center_axis',(0.,0.,1.));
+#4863=DIRECTION('ref_axis',(-0.827816715838139,0.560998649712242,0.));
+#4864=DIRECTION('',(0.,0.,1.));
+#4865=DIRECTION('center_axis',(0.,0.,-1.));
+#4866=DIRECTION('ref_axis',(1.,0.,0.));
+#4867=DIRECTION('',(0.,0.,-1.));
+#4868=DIRECTION('center_axis',(-1.,9.17912793601306E-16,0.));
+#4869=DIRECTION('ref_axis',(-9.17912793601306E-16,-1.,0.));
+#4870=DIRECTION('',(9.17912793601306E-16,1.,0.));
+#4871=DIRECTION('',(0.,0.,1.));
+#4872=DIRECTION('center_axis',(0.,0.,1.));
+#4873=DIRECTION('ref_axis',(1.,0.,0.));
+#4874=DIRECTION('center_axis',(0.,0.,-1.));
+#4875=DIRECTION('ref_axis',(1.,0.,0.));
+#4876=DIRECTION('',(0.,0.,1.));
+#4877=DIRECTION('center_axis',(0.,0.,1.));
+#4878=DIRECTION('ref_axis',(1.,0.,0.));
+#4879=DIRECTION('',(0.,0.,1.));
+#4880=DIRECTION('center_axis',(0.,0.,-1.));
+#4881=DIRECTION('ref_axis',(1.,0.,0.));
+#4882=DIRECTION('center_axis',(0.,0.,1.));
+#4883=DIRECTION('ref_axis',(1.,0.,0.));
+#4884=DIRECTION('',(0.,0.,1.));
+#4885=DIRECTION('',(0.,0.,1.));
+#4886=DIRECTION('center_axis',(0.,0.,1.));
+#4887=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4888=DIRECTION('center_axis',(0.,0.,-1.));
+#4889=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4890=DIRECTION('',(0.,0.,1.));
+#4891=DIRECTION('center_axis',(0.,0.,1.));
+#4892=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4893=DIRECTION('center_axis',(0.,0.,-1.));
+#4894=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#4895=DIRECTION('center_axis',(0.,0.,1.));
+#4896=DIRECTION('ref_axis',(1.,0.,0.));
+#4897=DIRECTION('center_axis',(0.,0.,-1.));
+#4898=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4899=DIRECTION('',(0.,1.,0.));
+#4900=DIRECTION('',(-1.,0.,0.));
+#4901=DIRECTION('',(0.,-1.,0.));
+#4902=DIRECTION('center_axis',(0.,0.,-1.));
+#4903=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4904=DIRECTION('',(4.58956396800653E-16,-1.,0.));
+#4905=DIRECTION('center_axis',(0.,0.,1.));
+#4906=DIRECTION('ref_axis',(0.,1.,0.));
+#4907=DIRECTION('center_axis',(1.,4.58956396800653E-16,0.));
+#4908=DIRECTION('ref_axis',(-4.58956396800653E-16,1.,0.));
+#4909=DIRECTION('center_axis',(0.,0.,1.));
+#4910=DIRECTION('ref_axis',(1.,0.,0.));
+#4911=DIRECTION('',(-1.,0.,0.));
+#4912=DIRECTION('center_axis',(0.,0.,1.));
+#4913=DIRECTION('ref_axis',(0.36363636363636,-0.931540978723601,0.));
+#4914=DIRECTION('',(0.,0.,1.));
+#4915=DIRECTION('',(0.,0.,1.));
+#4916=DIRECTION('center_axis',(0.,0.,1.));
+#4917=DIRECTION('ref_axis',(-1.22464679914735E-16,-1.,0.));
+#4918=DIRECTION('center_axis',(0.,0.,1.));
+#4919=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4920=DIRECTION('',(0.,0.,1.));
+#4921=DIRECTION('center_axis',(1.,0.,0.));
+#4922=DIRECTION('ref_axis',(0.,1.,0.));
+#4923=DIRECTION('',(0.,0.,-1.));
+#4924=DIRECTION('center_axis',(0.,-1.,0.));
+#4925=DIRECTION('ref_axis',(1.,0.,0.));
+#4926=DIRECTION('',(0.,0.,-1.));
+#4927=DIRECTION('center_axis',(-1.,0.,0.));
+#4928=DIRECTION('ref_axis',(0.,-1.,0.));
+#4929=DIRECTION('',(0.,0.,1.));
+#4930=DIRECTION('center_axis',(0.,0.,1.));
+#4931=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4932=DIRECTION('center_axis',(-1.,9.17912793601306E-16,0.));
+#4933=DIRECTION('ref_axis',(-9.17912793601306E-16,-1.,0.));
+#4934=DIRECTION('center_axis',(0.,0.,1.));
+#4935=DIRECTION('ref_axis',(-1.22464679914735E-16,-1.,0.));
+#4936=DIRECTION('center_axis',(1.,4.58956396800653E-16,0.));
+#4937=DIRECTION('ref_axis',(-4.58956396800653E-16,1.,0.));
+#4938=DIRECTION('center_axis',(0.,0.,1.));
+#4939=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#4940=DIRECTION('center_axis',(1.,0.,0.));
+#4941=DIRECTION('ref_axis',(0.,1.,0.));
+#4942=DIRECTION('center_axis',(-1.,0.,0.));
+#4943=DIRECTION('ref_axis',(0.,-1.,0.));
+#4944=DIRECTION('center_axis',(0.,0.,1.));
+#4945=DIRECTION('ref_axis',(1.,0.,0.));
+#4946=DIRECTION('center_axis',(0.,0.,1.));
+#4947=DIRECTION('ref_axis',(1.,0.,0.));
+#4948=DIRECTION('center_axis',(0.,0.,1.));
+#4949=DIRECTION('ref_axis',(1.,0.,0.));
+#4950=DIRECTION('center_axis',(0.,0.,1.));
+#4951=DIRECTION('ref_axis',(1.,0.,0.));
+#4952=DIRECTION('center_axis',(0.,0.,1.));
+#4953=DIRECTION('ref_axis',(1.,0.,0.));
+#4954=DIRECTION('center_axis',(0.,0.,1.));
+#4955=DIRECTION('ref_axis',(1.,0.,0.));
+#4956=DIRECTION('center_axis',(0.,0.,1.));
+#4957=DIRECTION('ref_axis',(1.,0.,0.));
+#4958=DIRECTION('center_axis',(0.,0.,1.));
+#4959=DIRECTION('ref_axis',(1.,0.,0.));
+#4960=DIRECTION('center_axis',(0.,0.,1.));
+#4961=DIRECTION('ref_axis',(1.,0.,0.));
+#4962=DIRECTION('center_axis',(0.,0.,1.));
+#4963=DIRECTION('ref_axis',(1.,0.,0.));
+#4964=DIRECTION('center_axis',(0.,0.,1.));
+#4965=DIRECTION('ref_axis',(1.,0.,0.));
+#4966=DIRECTION('center_axis',(0.,0.,1.));
+#4967=DIRECTION('ref_axis',(1.,0.,0.));
+#4968=DIRECTION('center_axis',(0.,0.,1.));
+#4969=DIRECTION('ref_axis',(1.,0.,0.));
+#4970=DIRECTION('center_axis',(0.,0.,1.));
+#4971=DIRECTION('ref_axis',(1.,0.,0.));
+#4972=DIRECTION('center_axis',(0.,0.,1.));
+#4973=DIRECTION('ref_axis',(1.,0.,0.));
+#4974=DIRECTION('center_axis',(0.,0.,1.));
+#4975=DIRECTION('ref_axis',(1.,0.,0.));
+#4976=DIRECTION('center_axis',(0.,0.,1.));
+#4977=DIRECTION('ref_axis',(1.,0.,0.));
+#4978=DIRECTION('center_axis',(0.,0.,1.));
+#4979=DIRECTION('ref_axis',(1.,0.,0.));
+#4980=DIRECTION('center_axis',(0.,0.,1.));
+#4981=DIRECTION('ref_axis',(1.,0.,0.));
+#4982=DIRECTION('center_axis',(0.,0.,1.));
+#4983=DIRECTION('ref_axis',(1.,0.,0.));
+#4984=DIRECTION('center_axis',(0.,0.,1.));
+#4985=DIRECTION('ref_axis',(1.,0.,0.));
+#4986=DIRECTION('center_axis',(0.,0.,1.));
+#4987=DIRECTION('ref_axis',(1.,0.,0.));
+#4988=DIRECTION('center_axis',(0.,0.,1.));
+#4989=DIRECTION('ref_axis',(1.,0.,0.));
+#4990=CARTESIAN_POINT('',(0.,0.,0.));
+#4991=CARTESIAN_POINT('Ctrl Pts',(-76.0341783761694,-92.5703721662834,13.5671347034882));
+#4992=CARTESIAN_POINT('Ctrl Pts',(-76.3653886617516,-93.1424854786047,13.5553578914238));
+#4993=CARTESIAN_POINT('Ctrl Pts',(-76.5287466825971,-93.8147725340562,13.5406286631181));
+#4994=CARTESIAN_POINT('Ctrl Pts',(-76.4832392371292,-94.4991962995851,13.5254012365491));
+#4995=CARTESIAN_POINT('Ctrl Pts',(-76.3843713776199,-92.599918309414,14.0311973254388));
+#4996=CARTESIAN_POINT('Ctrl Pts',(-76.7112792209379,-93.275646555984,14.0086637516235));
+#4997=CARTESIAN_POINT('Ctrl Pts',(-76.8197739172852,-94.0443953653359,13.9802505529048));
+#4998=CARTESIAN_POINT('Ctrl Pts',(-76.6969284956376,-94.7790765639352,13.9501938941736));
+#4999=CARTESIAN_POINT('Ctrl Pts',(-76.6064969522794,-92.7050483707038,14.5857153730199));
+#5000=CARTESIAN_POINT('Ctrl Pts',(-76.9158130399252,-93.45843016187,14.5481622183801));
+#5001=CARTESIAN_POINT('Ctrl Pts',(-76.9651243855666,-94.2936175204217,14.5005459394037));
+#5002=CARTESIAN_POINT('Ctrl Pts',(-76.7731530191055,-95.0510567054017,14.4482512388122));
+#5003=CARTESIAN_POINT('Ctrl Pts',(-76.6647400786385,-92.8688114186262,15.1412796197976));
+#5004=CARTESIAN_POINT('Ctrl Pts',(-76.9467215983432,-93.6616629705836,15.0886256656131));
+#5005=CARTESIAN_POINT('Ctrl Pts',(-76.9429977970269,-94.5239684607106,15.0217394310373));
+#5006=CARTESIAN_POINT('Ctrl Pts',(-76.7008163416603,-95.2755429263383,14.9470680441146));
+#5007=CARTESIAN_POINT('',(-76.7008163416603,-95.2755429263383,14.9470680441145));
+#5008=CARTESIAN_POINT('',(-76.4864231441389,-94.5033789439444,13.5317557066176));
+#5009=CARTESIAN_POINT('Ctrl Pts',(-76.7008163416603,-95.2755429263383,14.9470680441145));
+#5010=CARTESIAN_POINT('Ctrl Pts',(-76.7727926262792,-95.0521751314408,14.4507364234327));
+#5011=CARTESIAN_POINT('Ctrl Pts',(-76.6976843334517,-94.7817854816481,13.9551567147585));
+#5012=CARTESIAN_POINT('Ctrl Pts',(-76.4864229009137,-94.5033789303084,13.5317558369384));
+#5013=CARTESIAN_POINT('',(-76.8795324174535,-94.1253919759866,15.0494079886363));
+#5014=CARTESIAN_POINT('Ctrl Pts',(-76.7008163416603,-95.2755429263383,14.9470680441146));
+#5015=CARTESIAN_POINT('Ctrl Pts',(-76.8181780866844,-94.9113280418084,14.9832539868382));
+#5016=CARTESIAN_POINT('Ctrl Pts',(-76.8795405296548,-94.5211091268676,15.0176116674348));
+#5017=CARTESIAN_POINT('Ctrl Pts',(-76.8795267033468,-94.1253919271058,15.0494073777995));
+#5018=CARTESIAN_POINT('',(-76.6647400788017,-92.8688114190851,15.1412796197671));
+#5019=CARTESIAN_POINT('Ctrl Pts',(-76.8795267033468,-94.1253919271058,15.0494073777995));
+#5020=CARTESIAN_POINT('Ctrl Pts',(-76.8795119984594,-93.7045281590268,15.0832236043409));
+#5021=CARTESIAN_POINT('Ctrl Pts',(-76.8100726416845,-93.2774451059743,15.1141419048007));
+#5022=CARTESIAN_POINT('Ctrl Pts',(-76.6647400788017,-92.8688114190851,15.1412796197671));
+#5023=CARTESIAN_POINT('',(-76.0341783762574,-92.570372166323,13.5671347035781));
+#5024=CARTESIAN_POINT('Origin',(-73.8381846322518,-93.8740896430505,15.1412796197671));
+#5025=CARTESIAN_POINT('Ctrl Pts',(-76.4829390554398,-94.5023961897666,13.5314811596678));
+#5026=CARTESIAN_POINT('Ctrl Pts',(-76.5237287795492,-93.8362459662257,13.5463240562542));
+#5027=CARTESIAN_POINT('Ctrl Pts',(-76.3695197100186,-93.1503802433069,13.5583914472173));
+#5028=CARTESIAN_POINT('Ctrl Pts',(-76.0333073480428,-92.5670372854434,13.5668794147336));
+#5029=CARTESIAN_POINT('Ctrl Pts',(-123.55672536298,-105.829920952312,13.5493695952506));
+#5030=CARTESIAN_POINT('Ctrl Pts',(-123.556626904372,-106.76471797297,13.5493689609063));
+#5031=CARTESIAN_POINT('Ctrl Pts',(-122.943667157682,-108.1626519695,13.5454432621139));
+#5032=CARTESIAN_POINT('Ctrl Pts',(-121.225661425887,-109.142916227986,13.5341507420724));
+#5033=CARTESIAN_POINT('Ctrl Pts',(-119.544246325828,-109.297488344708,13.5229893019816));
+#5034=CARTESIAN_POINT('Ctrl Pts',(-118.224706422974,-108.695358655816,13.5142631976012));
+#5035=CARTESIAN_POINT('Ctrl Pts',(-117.500587847777,-107.896063691783,13.5095276576329));
+#5036=CARTESIAN_POINT('Ctrl Pts',(-116.897138788213,-106.976811864023,13.505597582932));
+#5037=CARTESIAN_POINT('Ctrl Pts',(-116.670174719094,-105.61311698168,13.5041367595203));
+#5038=CARTESIAN_POINT('Ctrl Pts',(-117.225472655981,-104.013457056817,13.5077286719218));
+#5039=CARTESIAN_POINT('Ctrl Pts',(-118.223116291451,-102.930297972709,13.5142434347057));
+#5040=CARTESIAN_POINT('Ctrl Pts',(-120.209880259906,-102.183172897523,13.5274165715883));
+#5041=CARTESIAN_POINT('Ctrl Pts',(-122.732273644581,-103.012488921549,13.5441022784986));
+#5042=CARTESIAN_POINT('Ctrl Pts',(-123.556725381661,-104.894775223385,13.549369595371));
+#5043=CARTESIAN_POINT('Ctrl Pts',(-123.556725381661,-105.829566219427,13.549369595371));
+#5044=CARTESIAN_POINT('Ctrl Pts',(-123.836911780944,-105.829959460236,14.0140396330936));
+#5045=CARTESIAN_POINT('Ctrl Pts',(-123.836799100993,-106.8664437553,14.0140383547098));
+#5046=CARTESIAN_POINT('Ctrl Pts',(-123.128951449108,-108.411134340958,14.0061341285421));
+#5047=CARTESIAN_POINT('Ctrl Pts',(-121.215154901317,-109.424931503051,13.9831838804179));
+#5048=CARTESIAN_POINT('Ctrl Pts',(-119.394955312129,-109.523986449429,13.9602648819289));
+#5049=CARTESIAN_POINT('Ctrl Pts',(-118.024399536055,-108.834790830646,13.9420381820148));
+#5050=CARTESIAN_POINT('Ctrl Pts',(-117.289600543228,-107.981109778082,13.9320403703173));
+#5051=CARTESIAN_POINT('Ctrl Pts',(-116.682214339901,-107.011352418731,13.9237121704861));
+#5052=CARTESIAN_POINT('Ctrl Pts',(-116.458335155416,-105.607956405479,13.9205860792201));
+#5053=CARTESIAN_POINT('Ctrl Pts',(-117.010042247958,-103.94651275003,13.9282441449152));
+#5054=CARTESIAN_POINT('Ctrl Pts',(-118.019688370013,-102.788795841132,13.9420156094969));
+#5055=CARTESIAN_POINT('Ctrl Pts',(-120.093959834384,-101.916270515443,13.969466255582));
+#5056=CARTESIAN_POINT('Ctrl Pts',(-122.882310863809,-102.71088521258,14.0034508256244));
+#5057=CARTESIAN_POINT('Ctrl Pts',(-123.836911802319,-104.793088603811,14.0140396333364));
+#5058=CARTESIAN_POINT('Ctrl Pts',(-123.836911802319,-105.829566219427,14.0140396333364));
+#5059=CARTESIAN_POINT('Ctrl Pts',(-123.987629565369,-105.829984371718,14.5558739203269));
+#5060=CARTESIAN_POINT('Ctrl Pts',(-123.987506708205,-106.93212346421,14.5558716699721));
+#5061=CARTESIAN_POINT('Ctrl Pts',(-123.210239700807,-108.570023190892,14.5420376732254));
+#5062=CARTESIAN_POINT('Ctrl Pts',(-121.167553251526,-109.585970144208,14.5011896825223));
+#5063=CARTESIAN_POINT('Ctrl Pts',(-119.269336069083,-109.631241599438,14.4598484603402));
+#5064=CARTESIAN_POINT('Ctrl Pts',(-117.888268299706,-108.882190233745,14.4262580653326));
+#5065=CARTESIAN_POINT('Ctrl Pts',(-117.162095421703,-108.002169473639,14.4075920656985));
+#5066=CARTESIAN_POINT('Ctrl Pts',(-116.565981122354,-107.01237787483,14.3919742051514));
+#5067=CARTESIAN_POINT('Ctrl Pts',(-116.350039010802,-105.608886483023,14.3860484049181));
+#5068=CARTESIAN_POINT('Ctrl Pts',(-116.885485290521,-103.93458825997,14.4005081588706));
+#5069=CARTESIAN_POINT('Ctrl Pts',(-117.880984414997,-102.740590319084,14.4262596996357));
+#5070=CARTESIAN_POINT('Ctrl Pts',(-119.980060445021,-101.778452756178,14.4766919719543));
+#5071=CARTESIAN_POINT('Ctrl Pts',(-122.937324656142,-102.517817670928,14.5373537426902));
+#5072=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-104.727434229031,14.5558739207541));
+#5073=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-105.829566219427,14.5558739207541));
+#5074=CARTESIAN_POINT('Ctrl Pts',(-123.987629564482,-105.829992174577,15.0984812132217));
+#5075=CARTESIAN_POINT('Ctrl Pts',(-123.987502063846,-106.952475097711,15.0984779848918));
+#5076=CARTESIAN_POINT('Ctrl Pts',(-123.176581303725,-108.61705348676,15.0786863558507));
+#5077=CARTESIAN_POINT('Ctrl Pts',(-121.089432918802,-109.604779931736,15.0198303743949));
+#5078=CARTESIAN_POINT('Ctrl Pts',(-119.183240304551,-109.606187103966,14.9599531646624));
+#5079=CARTESIAN_POINT('Ctrl Pts',(-117.832177765268,-108.832169773588,14.9109045773522));
+#5080=CARTESIAN_POINT('Ctrl Pts',(-117.132329286646,-107.956921091043,14.8835177343636));
+#5081=CARTESIAN_POINT('Ctrl Pts',(-116.560929137986,-106.979832244014,14.8605661699797));
+#5082=CARTESIAN_POINT('Ctrl Pts',(-116.356757262831,-105.615814991332,14.8518245967559));
+#5083=CARTESIAN_POINT('Ctrl Pts',(-116.865489110817,-103.978982989,14.8731260980557));
+#5084=CARTESIAN_POINT('Ctrl Pts',(-117.823168766352,-102.791112334497,14.9109305895696));
+#5085=CARTESIAN_POINT('Ctrl Pts',(-119.883269891983,-101.786902370026,14.9844847280587));
+#5086=CARTESIAN_POINT('Ctrl Pts',(-122.890360656589,-102.460274186555,15.0719887458894));
+#5087=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-104.707090529137,15.0984812138343));
+#5088=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-105.829566219427,15.0984812138343));
+#5089=CARTESIAN_POINT('',(-123.987629588674,-105.829566219427,15.0984812138343));
+#5090=CARTESIAN_POINT('',(-123.559587679644,-105.829566219427,13.55412646887));
+#5091=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-105.829566219427,15.0984812138343));
+#5092=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-105.829566219427,14.5577244732069));
+#5093=CARTESIAN_POINT('Ctrl Pts',(-123.837938089883,-105.829566219427,14.0177354745894));
+#5094=CARTESIAN_POINT('Ctrl Pts',(-123.559587575424,-105.829566219427,13.554126531444));
+#5095=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-105.829566219427,15.0984812138343));
+#5096=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-104.707090529137,15.0984812138343));
+#5097=CARTESIAN_POINT('Ctrl Pts',(-122.890360656589,-102.460274186555,15.0719887458894));
+#5098=CARTESIAN_POINT('Ctrl Pts',(-119.883269891983,-101.786902370026,14.9844847280587));
+#5099=CARTESIAN_POINT('Ctrl Pts',(-117.823168766352,-102.791112334497,14.9109305895696));
+#5100=CARTESIAN_POINT('Ctrl Pts',(-116.865489110817,-103.978982989,14.8731260980557));
+#5101=CARTESIAN_POINT('Ctrl Pts',(-116.356757262831,-105.615814991332,14.8518245967559));
+#5102=CARTESIAN_POINT('Ctrl Pts',(-116.560929137986,-106.979832244014,14.8605661699797));
+#5103=CARTESIAN_POINT('Ctrl Pts',(-117.132329286646,-107.956921091043,14.8835177343636));
+#5104=CARTESIAN_POINT('Ctrl Pts',(-117.832177765268,-108.832169773588,14.9109045773522));
+#5105=CARTESIAN_POINT('Ctrl Pts',(-119.183240304551,-109.606187103966,14.9599531646624));
+#5106=CARTESIAN_POINT('Ctrl Pts',(-121.089432918802,-109.604779931736,15.0198303743949));
+#5107=CARTESIAN_POINT('Ctrl Pts',(-123.176581303725,-108.61705348676,15.0786863558507));
+#5108=CARTESIAN_POINT('Ctrl Pts',(-123.987502063846,-106.952475097711,15.0984779848918));
+#5109=CARTESIAN_POINT('Ctrl Pts',(-123.987629564482,-105.829992174577,15.0984812132217));
+#5110=CARTESIAN_POINT('',(-123.559587660946,-105.82992134584,13.5541264687658));
+#5111=CARTESIAN_POINT('Origin',(-120.987629583836,-105.829651410457,15.0984812132217));
+#5112=CARTESIAN_POINT('',(-123.559587646219,-105.830041024796,13.5541264686837));
+#5113=CARTESIAN_POINT('Ctrl Pts',(-123.559587528198,-105.830041024908,13.5541265084479));
+#5114=CARTESIAN_POINT('Ctrl Pts',(-123.559587533889,-105.830001131886,13.5541265084848));
+#5115=CARTESIAN_POINT('Ctrl Pts',(-123.559587538835,-105.829961238859,13.5541265085169));
+#5116=CARTESIAN_POINT('Ctrl Pts',(-123.559587543039,-105.829921345827,13.5541265085443));
+#5117=CARTESIAN_POINT('Ctrl Pts',(-123.559587561729,-105.829566219427,13.5541265086348));
+#5118=CARTESIAN_POINT('Ctrl Pts',(-123.559587562252,-105.725165005732,13.5541265095068));
+#5119=CARTESIAN_POINT('Ctrl Pts',(-123.554456019888,-105.621024747544,13.5540982128762));
+#5120=CARTESIAN_POINT('Ctrl Pts',(-123.544425577012,-105.51745485186,13.5540425442219));
+#5121=CARTESIAN_POINT('Ctrl Pts',(-123.534049247221,-105.410313481599,13.5539849559056));
+#5122=CARTESIAN_POINT('Ctrl Pts',(-123.518430324175,-105.303781809262,13.5538980754039));
+#5123=CARTESIAN_POINT('Ctrl Pts',(-123.497771501166,-105.198193896322,13.5537825672145));
+#5124=CARTESIAN_POINT('Ctrl Pts',(-123.476852246677,-105.091274909661,13.5536656028933));
+#5125=CARTESIAN_POINT('Ctrl Pts',(-123.450765022431,-104.985322836176,13.5535192834658));
+#5126=CARTESIAN_POINT('Ctrl Pts',(-123.419666826234,-104.880687317402,13.5533439448837));
+#5127=CARTESIAN_POINT('Ctrl Pts',(-123.388475738473,-104.775739248122,13.5531680825582));
+#5128=CARTESIAN_POINT('Ctrl Pts',(-123.352243426077,-104.672114794558,13.55296302591));
+#5129=CARTESIAN_POINT('Ctrl Pts',(-123.311078546645,-104.570181652429,13.5527287807771));
+#5130=CARTESIAN_POINT('Ctrl Pts',(-123.305828046149,-104.557180277938,13.552698903265));
+#5131=CARTESIAN_POINT('Ctrl Pts',(-123.300497237175,-104.544206448113,13.5526685504747));
+#5132=CARTESIAN_POINT('Ctrl Pts',(-123.29508629068,-104.531260953948,13.5526377220499));
+#5133=CARTESIAN_POINT('Ctrl Pts',(-123.236008752457,-104.389920076342,13.5523011326111));
+#5134=CARTESIAN_POINT('Ctrl Pts',(-123.167695832726,-104.252710268546,13.5519096985289));
+#5135=CARTESIAN_POINT('Ctrl Pts',(-123.090757482089,-104.120817776499,13.5514635326821));
+#5136=CARTESIAN_POINT('Ctrl Pts',(-123.009269805207,-103.981126547274,13.5509909852717));
+#5137=CARTESIAN_POINT('Ctrl Pts',(-122.918106604182,-103.847399487429,13.5504570409029));
+#5138=CARTESIAN_POINT('Ctrl Pts',(-122.817939983614,-103.721016091509,13.5498615402245));
+#5139=CARTESIAN_POINT('Ctrl Pts',(-122.736563464053,-103.618340760827,13.5493777485948));
+#5140=CARTESIAN_POINT('Ctrl Pts',(-122.649243475585,-103.520511569491,13.5488533224688));
+#5141=CARTESIAN_POINT('Ctrl Pts',(-122.556316901064,-103.428259291489,13.5482880584863));
+#5142=CARTESIAN_POINT('Ctrl Pts',(-122.517013368965,-103.389240954824,13.5480489786408));
+#5143=CARTESIAN_POINT('Ctrl Pts',(-122.476713240366,-103.351227049457,13.5478025813479));
+#5144=CARTESIAN_POINT('Ctrl Pts',(-122.435449926163,-103.314277992914,13.5475488908093));
+#5145=CARTESIAN_POINT('Ctrl Pts',(-122.336755115359,-103.225902150705,13.5469421063037));
+#5146=CARTESIAN_POINT('Ctrl Pts',(-122.232549967316,-103.143621493496,13.5462935935859));
+#5147=CARTESIAN_POINT('Ctrl Pts',(-122.123821459218,-103.067834986543,13.5456077446014));
+#5148=CARTESIAN_POINT('Ctrl Pts',(-122.018177492979,-102.994198482907,13.5449413526106));
+#5149=CARTESIAN_POINT('Ctrl Pts',(-121.90826390663,-102.92669300791,13.5442397176003));
+#5150=CARTESIAN_POINT('Ctrl Pts',(-121.794984765295,-102.865636041815,13.5435069158962));
+#5151=CARTESIAN_POINT('Ctrl Pts',(-121.681705623959,-102.80457907572,13.5427741141921));
+#5152=CARTESIAN_POINT('Ctrl Pts',(-121.565061616835,-102.749970932013,13.5420101503247));
+#5153=CARTESIAN_POINT('Ctrl Pts',(-121.445944984264,-102.702076352851,13.5412190794898));
+#5154=CARTESIAN_POINT('Ctrl Pts',(-121.33942899161,-102.659248256287,13.5405116913323));
+#5155=CARTESIAN_POINT('Ctrl Pts',(-121.230727022866,-102.621705638575,13.5397809719033));
+#5156=CARTESIAN_POINT('Ctrl Pts',(-121.120485853132,-102.589670440958,13.539030771287));
+#5157=CARTESIAN_POINT('Ctrl Pts',(-121.01236099776,-102.55825022728,13.5382949723716));
+#5158=CARTESIAN_POINT('Ctrl Pts',(-120.902756072561,-102.532128124975,13.5375404373966));
+#5159=CARTESIAN_POINT('Ctrl Pts',(-120.792277301927,-102.511464864559,13.5367707930861));
+#5160=CARTESIAN_POINT('Ctrl Pts',(-120.685191555969,-102.491436214323,13.5360247860964));
+#5161=CARTESIAN_POINT('Ctrl Pts',(-120.577285272061,-102.476536219386,13.5352645869747));
+#5162=CARTESIAN_POINT('Ctrl Pts',(-120.469099079619,-102.466864640534,13.5344934371379));
+#5163=CARTESIAN_POINT('Ctrl Pts',(-120.360912887177,-102.457193061682,13.5337222873011));
+#5164=CARTESIAN_POINT('Ctrl Pts',(-120.252447255477,-102.452750078064,13.5329401901422));
+#5165=CARTESIAN_POINT('Ctrl Pts',(-120.144224260617,-102.453586656625,13.5321502742377));
+#5166=CARTESIAN_POINT('Ctrl Pts',(-120.035482640565,-102.454427244229,13.5313565729058));
+#5167=CARTESIAN_POINT('Ctrl Pts',(-119.92665495218,-102.460600436274,13.5305526715305));
+#5168=CARTESIAN_POINT('Ctrl Pts',(-119.818248308095,-102.472204337246,13.5297429634188));
+#5169=CARTESIAN_POINT('Ctrl Pts',(-119.783578702272,-102.475915389056,13.5294840100926));
+#5170=CARTESIAN_POINT('Ctrl Pts',(-119.748952043162,-102.480181511365,13.5292244619352));
+#5171=CARTESIAN_POINT('Ctrl Pts',(-119.714384547217,-102.485004834541,13.5289644597464));
+#5172=CARTESIAN_POINT('Ctrl Pts',(-119.606140889904,-102.500108449272,13.5281502964099));
+#5173=CARTESIAN_POINT('Ctrl Pts',(-119.498480115467,-102.52067827212,13.527331702902));
+#5174=CARTESIAN_POINT('Ctrl Pts',(-119.392083255684,-102.546462157147,13.5265143991052));
+#5175=CARTESIAN_POINT('Ctrl Pts',(-119.289152700836,-102.571406028586,13.5257237222613));
+#5176=CARTESIAN_POINT('Ctrl Pts',(-119.187405443637,-102.601229430472,13.5249342553697));
+#5177=CARTESIAN_POINT('Ctrl Pts',(-119.087421367649,-102.635673138718,13.5241508889299));
+#5178=CARTESIAN_POINT('Ctrl Pts',(-119.006049429449,-102.66370511552,13.5235133469525));
+#5179=CARTESIAN_POINT('Ctrl Pts',(-118.925844776922,-102.694796751625,13.5228798411619));
+#5180=CARTESIAN_POINT('Ctrl Pts',(-118.84709846572,-102.728794480033,13.5222528403419));
+#5181=CARTESIAN_POINT('Ctrl Pts',(-118.743876326419,-102.773359339061,13.5214309559261));
+#5182=CARTESIAN_POINT('Ctrl Pts',(-118.642780293799,-102.8230818588,13.5206179192902));
+#5183=CARTESIAN_POINT('Ctrl Pts',(-118.54443304927,-102.877717313632,13.5198202789269));
+#5184=CARTESIAN_POINT('Ctrl Pts',(-118.454874610435,-102.927470268716,13.5190939197285));
+#5185=CARTESIAN_POINT('Ctrl Pts',(-118.367595488221,-102.981296895097,13.5183803261291));
+#5186=CARTESIAN_POINT('Ctrl Pts',(-118.283033579425,-103.038992995015,13.5176841680726));
+#5187=CARTESIAN_POINT('Ctrl Pts',(-118.188291896624,-103.103634695696,13.5169042047686));
+#5188=CARTESIAN_POINT('Ctrl Pts',(-118.09696205588,-103.173132435275,13.5161461329713));
+#5189=CARTESIAN_POINT('Ctrl Pts',(-118.009540387329,-103.246918107486,13.5154151957115));
+#5190=CARTESIAN_POINT('Ctrl Pts',(-117.922118718778,-103.320703779696,13.5146842584517));
+#5191=CARTESIAN_POINT('Ctrl Pts',(-117.838605677642,-103.398776995275,13.513980457848));
+#5192=CARTESIAN_POINT('Ctrl Pts',(-117.759438231198,-103.480564668817,13.51330859623));
+#5193=CARTESIAN_POINT('Ctrl Pts',(-117.669833721105,-103.573134844421,13.5125481595374));
+#5194=CARTESIAN_POINT('Ctrl Pts',(-117.585412632714,-103.67085553923,13.5118266150219));
+#5195=CARTESIAN_POINT('Ctrl Pts',(-117.506801293802,-103.773098406411,13.5111509076478));
+#5196=CARTESIAN_POINT('Ctrl Pts',(-117.430316470945,-103.872575500847,13.5104934788401));
+#5197=CARTESIAN_POINT('Ctrl Pts',(-117.359331411156,-103.976333217672,13.5098794394961));
+#5198=CARTESIAN_POINT('Ctrl Pts',(-117.294374049729,-104.083799211707,13.5093148239623));
+#5199=CARTESIAN_POINT('Ctrl Pts',(-117.266346345023,-104.130168477337,13.5090712045001));
+#5200=CARTESIAN_POINT('Ctrl Pts',(-117.239440203236,-104.177228225945,13.508836781914));
+#5201=CARTESIAN_POINT('Ctrl Pts',(-117.213695049883,-104.224932999025,13.5086120202674));
+#5202=CARTESIAN_POINT('Ctrl Pts',(-117.157288012549,-104.329453056812,13.5081195726825));
+#5203=CARTESIAN_POINT('Ctrl Pts',(-117.106456628776,-104.437066793336,13.5076735162757));
+#5204=CARTESIAN_POINT('Ctrl Pts',(-117.061480235211,-104.546883630704,13.5072777726584));
+#5205=CARTESIAN_POINT('Ctrl Pts',(-117.056746504747,-104.558441767481,13.5072361209503));
+#5206=CARTESIAN_POINT('Ctrl Pts',(-117.05207759674,-104.570024340757,13.5071950263593));
+#5207=CARTESIAN_POINT('Ctrl Pts',(-117.047473811535,-104.581630335155,13.5071544933046));
+#5208=CARTESIAN_POINT('Ctrl Pts',(-116.993374445417,-104.718013096761,13.5066781868592));
+#5209=CARTESIAN_POINT('Ctrl Pts',(-116.948066971596,-104.858126439147,13.5062785572761));
+#5210=CARTESIAN_POINT('Ctrl Pts',(-116.912174845388,-105.000598357021,13.5059608389163));
+#5211=CARTESIAN_POINT('Ctrl Pts',(-116.889838150177,-105.089262700484,13.5057631137069));
+#5212=CARTESIAN_POINT('Ctrl Pts',(-116.871148280375,-105.178841631916,13.5055971158544));
+#5213=CARTESIAN_POINT('Ctrl Pts',(-116.856259797524,-105.26901353188,13.505464154757));
+#5214=CARTESIAN_POINT('Ctrl Pts',(-116.832305796145,-105.414090625211,13.50525023435));
+#5215=CARTESIAN_POINT('Ctrl Pts',(-116.818188803593,-105.560701472462,13.505121803873));
+#5216=CARTESIAN_POINT('Ctrl Pts',(-116.813566405599,-105.707543751583,13.5050786203049));
+#5217=CARTESIAN_POINT('Ctrl Pts',(-116.811963586196,-105.758461403942,13.5050636463755));
+#5218=CARTESIAN_POINT('Ctrl Pts',(-116.81150276518,-105.809407123207,13.5050589260236));
+#5219=CARTESIAN_POINT('Ctrl Pts',(-116.812170938278,-105.860327264054,13.5050644612629));
+#5220=CARTESIAN_POINT('Ctrl Pts',(-116.813674985467,-105.974947704264,13.505076921));
+#5221=CARTESIAN_POINT('Ctrl Pts',(-116.820896335528,-106.08950058866,13.5051413003775));
+#5222=CARTESIAN_POINT('Ctrl Pts',(-116.833737010493,-106.203467250812,13.5052560679376));
+#5223=CARTESIAN_POINT('Ctrl Pts',(-116.84644194639,-106.316229168788,13.5053696222871));
+#5224=CARTESIAN_POINT('Ctrl Pts',(-116.864648276495,-106.428418128795,13.5055325071551));
+#5225=CARTESIAN_POINT('Ctrl Pts',(-116.888309585523,-106.53951837225,13.5057435995117));
+#5226=CARTESIAN_POINT('Ctrl Pts',(-116.911139364653,-106.64671421744,13.505947273445));
+#5227=CARTESIAN_POINT('Ctrl Pts',(-116.939047822457,-106.752897227714,13.5061958289523));
+#5228=CARTESIAN_POINT('Ctrl Pts',(-116.972033870781,-106.857579865843,13.5064885570036));
+#5229=CARTESIAN_POINT('Ctrl Pts',(-117.000257911564,-106.94715006894,13.5067390255769));
+#5230=CARTESIAN_POINT('Ctrl Pts',(-117.032200008085,-107.03562173482,13.5070218385226));
+#5231=CARTESIAN_POINT('Ctrl Pts',(-117.067881697059,-107.122668692997,13.5073367149116));
+#5232=CARTESIAN_POINT('Ctrl Pts',(-117.104114148115,-107.211059258086,13.5076564515519));
+#5233=CARTESIAN_POINT('Ctrl Pts',(-117.14409881169,-107.297732705324,13.5080083819423));
+#5234=CARTESIAN_POINT('Ctrl Pts',(-117.187852525528,-107.382412579721,13.5083914374524));
+#5235=CARTESIAN_POINT('Ctrl Pts',(-117.195781912116,-107.397758921813,13.508460857736));
+#5236=CARTESIAN_POINT('Ctrl Pts',(-117.20383519983,-107.413039708097,13.5085313010276));
+#5237=CARTESIAN_POINT('Ctrl Pts',(-117.212012637042,-107.428253179949,13.5086027619543));
+#5238=CARTESIAN_POINT('Ctrl Pts',(-117.259274408893,-107.516179949317,13.50901577277));
+#5239=CARTESIAN_POINT('Ctrl Pts',(-117.31068089492,-107.601861732239,13.5094627612716));
+#5240=CARTESIAN_POINT('Ctrl Pts',(-117.365806452336,-107.685113654319,13.5099397243523));
+#5241=CARTESIAN_POINT('Ctrl Pts',(-117.411358745021,-107.753907805324,13.5103338566364));
+#5242=CARTESIAN_POINT('Ctrl Pts',(-117.459451512994,-107.821042225182,13.5107484628697));
+#5243=CARTESIAN_POINT('Ctrl Pts',(-117.509854128299,-107.88638745012,13.5111813440961));
+#5244=CARTESIAN_POINT('Ctrl Pts',(-117.566986074949,-107.960457017392,13.5116720199666));
+#5245=CARTESIAN_POINT('Ctrl Pts',(-117.627084628928,-108.032228907438,13.5121861681189));
+#5246=CARTESIAN_POINT('Ctrl Pts',(-117.690153477578,-108.101484436282,13.5127227902475));
+#5247=CARTESIAN_POINT('Ctrl Pts',(-117.717431014662,-108.131437738059,13.5129548815307));
+#5248=CARTESIAN_POINT('Ctrl Pts',(-117.74526441666,-108.160919734438,13.5131911784058));
+#5249=CARTESIAN_POINT('Ctrl Pts',(-117.773655001021,-108.189909849578,13.5134316069304));
+#5250=CARTESIAN_POINT('Ctrl Pts',(-117.805306481451,-108.222229721912,13.513699650682));
+#5251=CARTESIAN_POINT('Ctrl Pts',(-117.837554906843,-108.253840824024,13.5139721445602));
+#5252=CARTESIAN_POINT('Ctrl Pts',(-117.870395181223,-108.284727644219,13.5142489409169));
+#5253=CARTESIAN_POINT('Ctrl Pts',(-117.94013513157,-108.350319218815,13.5148367485567));
+#5254=CARTESIAN_POINT('Ctrl Pts',(-118.012542584681,-108.412647733809,13.5154439500504));
+#5255=CARTESIAN_POINT('Ctrl Pts',(-118.087450687767,-108.471722989041,13.5160681118902));
+#5256=CARTESIAN_POINT('Ctrl Pts',(-118.161314479634,-108.529974662453,13.5166835721452));
+#5257=CARTESIAN_POINT('Ctrl Pts',(-118.237610460655,-108.585063211845,13.517315528527));
+#5258=CARTESIAN_POINT('Ctrl Pts',(-118.316197458993,-108.636948704084,13.517961753039));
+#5259=CARTESIAN_POINT('Ctrl Pts',(-118.396451091591,-108.689934558225,13.5186216823615));
+#5260=CARTESIAN_POINT('Ctrl Pts',(-118.479094710975,-108.739580470088,13.519296496865));
+#5261=CARTESIAN_POINT('Ctrl Pts',(-118.563986209276,-108.785788127098,13.5199838532047));
+#5262=CARTESIAN_POINT('Ctrl Pts',(-118.648877707578,-108.831995784107,13.5206712095444));
+#5263=CARTESIAN_POINT('Ctrl Pts',(-118.736017947715,-108.874765453213,13.5213711137419));
+#5264=CARTESIAN_POINT('Ctrl Pts',(-118.82526062797,-108.913938772267,13.5220811647421));
+#5265=CARTESIAN_POINT('Ctrl Pts',(-118.92009147573,-108.955565032761,13.522835677472));
+#5266=CARTESIAN_POINT('Ctrl Pts',(-119.016612513356,-108.992829708619,13.5235969275383));
+#5267=CARTESIAN_POINT('Ctrl Pts',(-119.114518737409,-109.025646250693,13.5243620380226));
+#5268=CARTESIAN_POINT('Ctrl Pts',(-119.212268260291,-109.058410269135,13.5251259239299));
+#5269=CARTESIAN_POINT('Ctrl Pts',(-119.311399370217,-109.086740550555,13.5258936634834));
+#5270=CARTESIAN_POINT('Ctrl Pts',(-119.411604106576,-109.110498459176,13.5266623409618));
+#5271=CARTESIAN_POINT('Ctrl Pts',(-119.511808842935,-109.134256367796,13.5274310184403));
+#5272=CARTESIAN_POINT('Ctrl Pts',(-119.613088068463,-109.153442114277,13.5282006396213));
+#5273=CARTESIAN_POINT('Ctrl Pts',(-119.715116718622,-109.167861651307,13.5289681511298));
+#5274=CARTESIAN_POINT('Ctrl Pts',(-119.81790455911,-109.182388483425,13.5297413736549));
+#5275=CARTESIAN_POINT('Ctrl Pts',(-119.921453149003,-109.192076719449,13.5305124562701));
+#5276=CARTESIAN_POINT('Ctrl Pts',(-120.025533726443,-109.196906425002,13.5312788438193));
+#5277=CARTESIAN_POINT('Ctrl Pts',(-120.043686218538,-109.197748764601,13.5314125079887));
+#5278=CARTESIAN_POINT('Ctrl Pts',(-120.061854821753,-109.198443209958,13.5315460287963));
+#5279=CARTESIAN_POINT('Ctrl Pts',(-120.080038226844,-109.198989521661,13.5316793919541));
+#5280=CARTESIAN_POINT('Ctrl Pts',(-120.200321446919,-109.202603373442,13.5325615892092));
+#5281=CARTESIAN_POINT('Ctrl Pts',(-120.320567490532,-109.19971837285,13.5334323779206));
+#5282=CARTESIAN_POINT('Ctrl Pts',(-120.440301769032,-109.190458329847,13.5342887606939));
+#5283=CARTESIAN_POINT('Ctrl Pts',(-120.558113493567,-109.181346973859,13.5351313926673));
+#5284=CARTESIAN_POINT('Ctrl Pts',(-120.675430452836,-109.166063278794,13.5359600824678));
+#5285=CARTESIAN_POINT('Ctrl Pts',(-120.791769975739,-109.144685578657,13.5367717733885));
+#5286=CARTESIAN_POINT('Ctrl Pts',(-120.904487819684,-109.123973371766,13.5375581961642));
+#5287=CARTESIAN_POINT('Ctrl Pts',(-121.01628865064,-109.09754026446,13.5383286655698));
+#5288=CARTESIAN_POINT('Ctrl Pts',(-121.12669590263,-109.065425854834,13.5390801504639));
+#5289=CARTESIAN_POINT('Ctrl Pts',(-121.147217414947,-109.059456715662,13.5392198297533));
+#5290=CARTESIAN_POINT('Ctrl Pts',(-121.167690661956,-109.053291217579,13.5393588523596));
+#5291=CARTESIAN_POINT('Ctrl Pts',(-121.188112412168,-109.04692950614,13.5394971976663));
+#5292=CARTESIAN_POINT('Ctrl Pts',(-121.244677576189,-109.029308526191,13.5398803932731));
+#5293=CARTESIAN_POINT('Ctrl Pts',(-121.3008479001,-109.010182275461,13.540258394122));
+#5294=CARTESIAN_POINT('Ctrl Pts',(-121.356559371975,-108.989567825177,13.5406308428782));
+#5295=CARTESIAN_POINT('Ctrl Pts',(-121.471288399526,-108.947115602054,13.5413978426032));
+#5296=CARTESIAN_POINT('Ctrl Pts',(-121.583545187285,-108.898550196009,13.542138046256));
+#5297=CARTESIAN_POINT('Ctrl Pts',(-121.692806343201,-108.844166069392,13.5428497139667));
+#5298=CARTESIAN_POINT('Ctrl Pts',(-121.799903314532,-108.790859153496,13.5435472853567));
+#5299=CARTESIAN_POINT('Ctrl Pts',(-121.904122760143,-108.731961184408,13.5442174443365));
+#5300=CARTESIAN_POINT('Ctrl Pts',(-122.00493289394,-108.66771940771,13.5448583326654));
+#5301=CARTESIAN_POINT('Ctrl Pts',(-122.101826028921,-108.60597375867,13.5454743191444));
+#5302=CARTESIAN_POINT('Ctrl Pts',(-122.195570009678,-108.539290979312,13.5460632681762));
+#5303=CARTESIAN_POINT('Ctrl Pts',(-122.285649598252,-108.467870456784,13.5466232755254));
+#5304=CARTESIAN_POINT('Ctrl Pts',(-122.338625915752,-108.425867641969,13.5469526190272));
+#5305=CARTESIAN_POINT('Ctrl Pts',(-122.39033399384,-108.382225847997,13.5472719475033));
+#5306=CARTESIAN_POINT('Ctrl Pts',(-122.440660852916,-108.336983236724,13.5475808240641));
+#5307=CARTESIAN_POINT('Ctrl Pts',(-122.450188616488,-108.328418011087,13.5476392998541));
+#5308=CARTESIAN_POINT('Ctrl Pts',(-122.459666856299,-108.31979540596,13.547697400917));
+#5309=CARTESIAN_POINT('Ctrl Pts',(-122.46909524653,-108.311115885021,13.5477551274096));
+#5310=CARTESIAN_POINT('Ctrl Pts',(-122.552173668617,-108.234636137534,13.5482637853876));
+#5311=CARTESIAN_POINT('Ctrl Pts',(-122.630987809976,-108.154105912986,13.5487409793202));
+#5312=CARTESIAN_POINT('Ctrl Pts',(-122.705444761711,-108.069912561827,13.5491876579143));
+#5313=CARTESIAN_POINT('Ctrl Pts',(-122.780339981588,-107.98522363218,13.5496369657457));
+#5314=CARTESIAN_POINT('Ctrl Pts',(-122.850826913874,-107.896827593404,13.5500554002341));
+#5315=CARTESIAN_POINT('Ctrl Pts',(-122.916767228891,-107.805088573085,13.5504436518683));
+#5316=CARTESIAN_POINT('Ctrl Pts',(-122.982103403358,-107.714190059248,13.5508283463682));
+#5317=CARTESIAN_POINT('Ctrl Pts',(-123.042976138184,-107.620008766241,13.5511834102103));
+#5318=CARTESIAN_POINT('Ctrl Pts',(-123.099203753272,-107.522880775027,13.5515092173798));
+#5319=CARTESIAN_POINT('Ctrl Pts',(-123.149413426133,-107.436148220981,13.5518001539841));
+#5320=CARTESIAN_POINT('Ctrl Pts',(-123.195918622481,-107.347065370203,13.5520677584768));
+#5321=CARTESIAN_POINT('Ctrl Pts',(-123.23855514428,-107.255866639568,13.5523120760794));
+#5322=CARTESIAN_POINT('Ctrl Pts',(-123.287930707974,-107.150253223104,13.5525950100252));
+#5323=CARTESIAN_POINT('Ctrl Pts',(-123.33190706372,-107.042254828448,13.5528452439338));
+#5324=CARTESIAN_POINT('Ctrl Pts',(-123.370309327571,-106.932301675794,13.5530627944109));
+#5325=CARTESIAN_POINT('Ctrl Pts',(-123.408190809358,-106.823839623509,13.5532773946352));
+#5326=CARTESIAN_POINT('Ctrl Pts',(-123.440648557882,-106.713474676602,13.5534601931285));
+#5327=CARTESIAN_POINT('Ctrl Pts',(-123.4674649628,-106.60161080713,13.553610877158));
+#5328=CARTESIAN_POINT('Ctrl Pts',(-123.470844232064,-106.587514281626,13.553629865606));
+#5329=CARTESIAN_POINT('Ctrl Pts',(-123.474133850041,-106.573393950808,13.5536483436348));
+#5330=CARTESIAN_POINT('Ctrl Pts',(-123.477333321658,-106.559250622552,13.5536663102257));
+#5331=CARTESIAN_POINT('Ctrl Pts',(-123.498784638951,-106.464424645529,13.5537867698165));
+#5332=CARTESIAN_POINT('Ctrl Pts',(-123.516111677813,-106.36890233334,13.5538837798598));
+#5333=CARTESIAN_POINT('Ctrl Pts',(-123.529242246858,-106.272863056228,13.5539571857986));
+#5334=CARTESIAN_POINT('Ctrl Pts',(-123.542174647214,-106.178273219542,13.554029483883));
+#5335=CARTESIAN_POINT('Ctrl Pts',(-123.551036400946,-106.08318124729,13.5540788854751));
+#5336=CARTESIAN_POINT('Ctrl Pts',(-123.555708876769,-105.987751862301,13.5541049139342));
+#5337=CARTESIAN_POINT('Ctrl Pts',(-123.558278308641,-105.935274479292,13.5541192271924));
+#5338=CARTESIAN_POINT('Ctrl Pts',(-123.559580021655,-105.882695002313,13.5541264665917));
+#5339=CARTESIAN_POINT('Ctrl Pts',(-123.559587528198,-105.830041024908,13.5541265084479));
+#5340=CARTESIAN_POINT('Origin',(-73.1315457706143,-108.379566219427,11.5));
+#5341=CARTESIAN_POINT('',(-75.8810911875878,-108.379566219427,14.9843134832984));
+#5342=CARTESIAN_POINT('',(-75.8810911875878,-108.379566219427,20.));
+#5343=CARTESIAN_POINT('',(-75.8810911875878,-108.379566219427,13.));
+#5344=CARTESIAN_POINT('',(-75.3424562165618,-108.379566219427,13.5319447284707));
+#5345=CARTESIAN_POINT('Ctrl Pts',(-75.3424562165618,-108.379566219427,13.5319447284707));
+#5346=CARTESIAN_POINT('Ctrl Pts',(-75.3853590599865,-108.379566219427,13.5827414708125));
+#5347=CARTESIAN_POINT('Ctrl Pts',(-75.4251825189192,-108.379566219427,13.6342742062064));
+#5348=CARTESIAN_POINT('Ctrl Pts',(-75.5912586222024,-108.379566219427,13.8674166428326));
+#5349=CARTESIAN_POINT('Ctrl Pts',(-75.7117522326224,-108.379566219427,14.107551063781));
+#5350=CARTESIAN_POINT('Ctrl Pts',(-75.8423763843037,-108.379566219427,14.5225958083955));
+#5351=CARTESIAN_POINT('Ctrl Pts',(-75.8810911875878,-108.379566219427,14.773089947923));
+#5352=CARTESIAN_POINT('Ctrl Pts',(-75.8810911875878,-108.379566219427,14.9843134832984));
+#5353=CARTESIAN_POINT('',(-74.7118938335422,-108.379566219427,12.0795759736429));
+#5354=CARTESIAN_POINT('Ctrl Pts',(-74.7118938335422,-108.379566219427,12.0795759736429));
+#5355=CARTESIAN_POINT('Ctrl Pts',(-74.7118938335422,-108.379566219427,12.2290208264313));
+#5356=CARTESIAN_POINT('Ctrl Pts',(-74.7392675440001,-108.379566219427,12.406253160309));
+#5357=CARTESIAN_POINT('Ctrl Pts',(-74.829748809299,-108.379566219427,12.7159930670314));
+#5358=CARTESIAN_POINT('Ctrl Pts',(-74.9158813616897,-108.379566219427,12.9051985737349));
+#5359=CARTESIAN_POINT('Ctrl Pts',(-75.0960200530301,-108.379566219427,13.2151851992955));
+#5360=CARTESIAN_POINT('Ctrl Pts',(-75.2122745353172,-108.379566219427,13.3778102983967));
+#5361=CARTESIAN_POINT('Ctrl Pts',(-75.3424562165618,-108.379566219427,13.5319447284707));
+#5362=CARTESIAN_POINT('',(-74.7118938335422,-108.379566219427,3.));
+#5363=CARTESIAN_POINT('',(-74.7118938335422,-108.379566219427,3.));
+#5364=CARTESIAN_POINT('',(-71.5511977076864,-108.379566219427,3.));
+#5365=CARTESIAN_POINT('',(-76.8815457706143,-108.379566219427,3.));
+#5366=CARTESIAN_POINT('',(-71.5511977076864,-108.379566219427,12.0795759736429));
+#5367=CARTESIAN_POINT('',(-71.5511977076864,-108.379566219427,3.));
+#5368=CARTESIAN_POINT('',(-70.9206353246667,-108.379566219427,13.5319447284707));
+#5369=CARTESIAN_POINT('Ctrl Pts',(-70.9206353246667,-108.379566219427,13.5319447284707));
+#5370=CARTESIAN_POINT('Ctrl Pts',(-71.0508170059114,-108.379566219427,13.3778102983967));
+#5371=CARTESIAN_POINT('Ctrl Pts',(-71.1670714881984,-108.379566219427,13.2151851992955));
+#5372=CARTESIAN_POINT('Ctrl Pts',(-71.3472101795389,-108.379566219427,12.9051985737349));
+#5373=CARTESIAN_POINT('Ctrl Pts',(-71.4333427319296,-108.379566219427,12.7159930670314));
+#5374=CARTESIAN_POINT('Ctrl Pts',(-71.5238239972285,-108.379566219427,12.406253160309));
+#5375=CARTESIAN_POINT('Ctrl Pts',(-71.5511977076864,-108.379566219427,12.2290208264313));
+#5376=CARTESIAN_POINT('Ctrl Pts',(-71.5511977076864,-108.379566219427,12.0795759736429));
+#5377=CARTESIAN_POINT('',(-70.3820003536408,-108.379566219427,14.9843134832984));
+#5378=CARTESIAN_POINT('Ctrl Pts',(-70.3820003536408,-108.379566219427,14.9843134832984));
+#5379=CARTESIAN_POINT('Ctrl Pts',(-70.3820003536408,-108.379566219427,14.773089947923));
+#5380=CARTESIAN_POINT('Ctrl Pts',(-70.4207151569249,-108.379566219427,14.5225958083955));
+#5381=CARTESIAN_POINT('Ctrl Pts',(-70.5513393086062,-108.379566219427,14.107551063781));
+#5382=CARTESIAN_POINT('Ctrl Pts',(-70.6718329190262,-108.379566219427,13.8674166428326));
+#5383=CARTESIAN_POINT('Ctrl Pts',(-70.8379090223094,-108.379566219427,13.6342742062064));
+#5384=CARTESIAN_POINT('Ctrl Pts',(-70.8777324812421,-108.379566219427,13.5827414708125));
+#5385=CARTESIAN_POINT('Ctrl Pts',(-70.9206353246667,-108.379566219427,13.5319447284707));
+#5386=CARTESIAN_POINT('',(-70.3820003536408,-108.379566219427,20.));
+#5387=CARTESIAN_POINT('',(-70.3820003536408,-108.379566219427,13.));
+#5388=CARTESIAN_POINT('',(-73.1315457706143,-108.379566219427,20.));
+#5389=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,20.));
+#5390=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,20.));
+#5391=CARTESIAN_POINT('',(-74.6315457706143,-105.829566219427,20.));
+#5392=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,20.));
+#5393=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,13.));
+#5394=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,14.9843134832984));
+#5395=CARTESIAN_POINT('Ctrl Pts',(-75.3424562165618,-108.379566219427,13.5319447284707));
+#5396=CARTESIAN_POINT('Ctrl Pts',(-77.1126729946995,-106.844746311044,13.5319447284707));
+#5397=CARTESIAN_POINT('Ctrl Pts',(-76.2935763681892,-104.649656265235,13.5319447284707));
+#5398=CARTESIAN_POINT('Ctrl Pts',(-75.4744797416789,-102.454566219427,13.5319447284707));
+#5399=CARTESIAN_POINT('Ctrl Pts',(-73.1315457706143,-102.454566219427,13.5319447284707));
+#5400=CARTESIAN_POINT('Ctrl Pts',(-70.7886117995497,-102.454566219427,13.5319447284707));
+#5401=CARTESIAN_POINT('Ctrl Pts',(-69.9695151730394,-104.649656265235,13.5319447284707));
+#5402=CARTESIAN_POINT('Ctrl Pts',(-69.1504185465291,-106.844746311044,13.5319447284707));
+#5403=CARTESIAN_POINT('Ctrl Pts',(-70.9206353246668,-108.379566219427,13.5319447284707));
+#5404=CARTESIAN_POINT('Ctrl Pts',(-75.5881129327782,-108.66289955276,14.209716814057));
+#5405=CARTESIAN_POINT('Ctrl Pts',(-77.5550204640423,-106.957544099001,14.209716814057));
+#5406=CARTESIAN_POINT('Ctrl Pts',(-76.6449131012531,-104.518555159214,14.209716814057));
+#5407=CARTESIAN_POINT('Ctrl Pts',(-75.7348057384638,-102.079566219427,14.209716814057));
+#5408=CARTESIAN_POINT('Ctrl Pts',(-73.1315457706143,-102.079566219427,14.209716814057));
+#5409=CARTESIAN_POINT('Ctrl Pts',(-70.5282858027647,-102.079566219427,14.209716814057));
+#5410=CARTESIAN_POINT('Ctrl Pts',(-69.6181784399755,-104.518555159214,14.209716814057));
+#5411=CARTESIAN_POINT('Ctrl Pts',(-68.7080710771862,-106.957544099001,14.209716814057));
+#5412=CARTESIAN_POINT('Ctrl Pts',(-70.6749786084504,-108.66289955276,14.209716814057));
+#5413=CARTESIAN_POINT('Ctrl Pts',(-75.5881129327782,-108.66289955276,14.9843134832984));
+#5414=CARTESIAN_POINT('Ctrl Pts',(-77.5550204640423,-106.957544099001,14.9843134832984));
+#5415=CARTESIAN_POINT('Ctrl Pts',(-76.6449131012531,-104.518555159214,14.9843134832984));
+#5416=CARTESIAN_POINT('Ctrl Pts',(-75.7348057384638,-102.079566219427,14.9843134832984));
+#5417=CARTESIAN_POINT('Ctrl Pts',(-73.1315457706143,-102.079566219427,14.9843134832984));
+#5418=CARTESIAN_POINT('Ctrl Pts',(-70.5282858027647,-102.079566219427,14.9843134832984));
+#5419=CARTESIAN_POINT('Ctrl Pts',(-69.6181784399755,-104.518555159214,14.9843134832984));
+#5420=CARTESIAN_POINT('Ctrl Pts',(-68.7080710771862,-106.957544099001,14.9843134832984));
+#5421=CARTESIAN_POINT('Ctrl Pts',(-70.6749786084504,-108.66289955276,14.9843134832984));
+#5422=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,13.5319447284707));
+#5423=CARTESIAN_POINT('Origin',(-159.181545770614,-111.187409348464,3.));
+#5424=CARTESIAN_POINT('',(-159.181545770614,-111.187409348464,3.));
+#5425=CARTESIAN_POINT('',(-159.181545770614,-120.187409348464,3.));
+#5426=CARTESIAN_POINT('',(-159.181545770614,-108.749289100439,3.));
+#5427=CARTESIAN_POINT('',(-159.181545770614,-111.187409348464,2.));
+#5428=CARTESIAN_POINT('',(-159.181545770614,-111.187409348464,3.));
+#5429=CARTESIAN_POINT('',(-159.181545770614,-120.187409348464,2.));
+#5430=CARTESIAN_POINT('',(-159.181545770614,-125.188933033705,2.));
+#5431=CARTESIAN_POINT('',(-159.181545770614,-120.187409348464,3.));
+#5432=CARTESIAN_POINT('Origin',(-164.181545770614,-111.187409348464,3.));
+#5433=CARTESIAN_POINT('',(-164.181545770614,-111.187409348464,3.));
+#5434=CARTESIAN_POINT('',(-149.181545770614,-111.187409348464,3.));
+#5435=CARTESIAN_POINT('',(-164.181545770614,-111.187409348464,2.));
+#5436=CARTESIAN_POINT('',(-164.181545770614,-111.187409348464,3.));
+#5437=CARTESIAN_POINT('',(-159.181545770614,-111.187409348464,2.));
+#5438=CARTESIAN_POINT('Origin',(-164.181545770614,-120.187409348464,3.));
+#5439=CARTESIAN_POINT('',(-164.181545770614,-120.187409348464,3.));
+#5440=CARTESIAN_POINT('',(-164.181545770614,-113.249289100439,3.));
+#5441=CARTESIAN_POINT('',(-164.181545770614,-120.187409348464,2.));
+#5442=CARTESIAN_POINT('',(-164.181545770614,-120.187409348464,3.));
+#5443=CARTESIAN_POINT('',(-164.181545770614,-111.187409348464,2.));
+#5444=CARTESIAN_POINT('Origin',(-159.181545770614,-120.187409348464,3.));
+#5445=CARTESIAN_POINT('',(-146.681545770614,-120.187409348464,3.));
+#5446=CARTESIAN_POINT('',(-164.181545770614,-120.187409348464,2.));
+#5447=CARTESIAN_POINT('Origin',(-161.681545770614,-115.687409348464,2.));
+#5448=CARTESIAN_POINT('Origin',(-134.181545770614,-112.982328591576,3.));
+#5449=CARTESIAN_POINT('',(-134.181545770614,-112.982328591576,3.));
+#5450=CARTESIAN_POINT('',(-134.181545770614,-121.982328591576,3.));
+#5451=CARTESIAN_POINT('',(-134.181545770614,-109.646748721995,3.));
+#5452=CARTESIAN_POINT('',(-134.181545770614,-112.982328591576,2.));
+#5453=CARTESIAN_POINT('',(-134.181545770614,-112.982328591576,3.));
+#5454=CARTESIAN_POINT('',(-134.181545770614,-121.982328591576,2.));
+#5455=CARTESIAN_POINT('',(-134.181545770614,-141.311168852415,2.));
+#5456=CARTESIAN_POINT('',(-134.181545770614,-121.982328591576,3.));
+#5457=CARTESIAN_POINT('Origin',(-139.181545770614,-112.982328591576,3.));
+#5458=CARTESIAN_POINT('',(-139.181545770614,-112.982328591576,3.));
+#5459=CARTESIAN_POINT('',(-136.681545770614,-112.982328591576,3.));
+#5460=CARTESIAN_POINT('',(-139.181545770614,-112.982328591576,2.));
+#5461=CARTESIAN_POINT('',(-139.181545770614,-112.982328591576,3.));
+#5462=CARTESIAN_POINT('',(-134.181545770614,-112.982328591576,2.));
+#5463=CARTESIAN_POINT('Origin',(-139.181545770614,-121.982328591576,3.));
+#5464=CARTESIAN_POINT('',(-139.181545770614,-121.982328591576,3.));
+#5465=CARTESIAN_POINT('',(-139.181545770614,-114.146748721995,3.));
+#5466=CARTESIAN_POINT('',(-139.181545770614,-121.982328591576,2.));
+#5467=CARTESIAN_POINT('',(-139.181545770614,-121.982328591576,3.));
+#5468=CARTESIAN_POINT('',(-139.181545770614,-112.982328591576,2.));
+#5469=CARTESIAN_POINT('Origin',(-134.181545770614,-121.982328591576,3.));
+#5470=CARTESIAN_POINT('',(-134.181545770614,-121.982328591576,3.));
+#5471=CARTESIAN_POINT('',(-139.181545770614,-121.982328591576,2.));
+#5472=CARTESIAN_POINT('Origin',(-136.681545770614,-117.482328591576,2.));
+#5473=CARTESIAN_POINT('Origin',(-84.1815457706141,-114.68742690406,3.));
+#5474=CARTESIAN_POINT('',(-84.1815457706141,-114.68742690406,3.));
+#5475=CARTESIAN_POINT('',(-89.1815457706141,-114.68742690406,3.));
+#5476=CARTESIAN_POINT('',(-109.181545770614,-114.68742690406,3.));
+#5477=CARTESIAN_POINT('',(-84.1815457706141,-114.68742690406,2.));
+#5478=CARTESIAN_POINT('',(-84.1815457706141,-114.68742690406,3.));
+#5479=CARTESIAN_POINT('',(-89.1815457706141,-114.68742690406,2.));
+#5480=CARTESIAN_POINT('',(-89.1815457706141,-114.68742690406,2.));
+#5481=CARTESIAN_POINT('',(-89.1815457706141,-114.68742690406,3.));
+#5482=CARTESIAN_POINT('Origin',(-84.1815457706142,-105.68742690406,3.));
+#5483=CARTESIAN_POINT('',(-84.1815457706141,-105.68742690406,3.));
+#5484=CARTESIAN_POINT('',(-84.1815457706142,-105.999297878238,3.));
+#5485=CARTESIAN_POINT('',(-84.1815457706141,-105.68742690406,2.));
+#5486=CARTESIAN_POINT('',(-84.1815457706141,-105.68742690406,3.));
+#5487=CARTESIAN_POINT('',(-84.1815457706142,-124.769126886663,2.));
+#5488=CARTESIAN_POINT('Origin',(-89.1815457706141,-105.68742690406,3.));
+#5489=CARTESIAN_POINT('',(-89.1815457706141,-105.68742690406,3.));
+#5490=CARTESIAN_POINT('',(-111.681545770614,-105.68742690406,3.));
+#5491=CARTESIAN_POINT('',(-89.1815457706141,-105.68742690406,2.));
+#5492=CARTESIAN_POINT('',(-89.1815457706141,-105.68742690406,3.));
+#5493=CARTESIAN_POINT('',(-84.1815457706141,-105.68742690406,2.));
+#5494=CARTESIAN_POINT('Origin',(-89.1815457706141,-114.68742690406,3.));
+#5495=CARTESIAN_POINT('',(-89.1815457706141,-110.499297878238,3.));
+#5496=CARTESIAN_POINT('',(-89.1815457706141,-105.68742690406,2.));
+#5497=CARTESIAN_POINT('Origin',(-86.6815457706141,-105.758496561743,2.));
+#5498=CARTESIAN_POINT('Origin',(-184.181545770614,-105.68742690406,3.));
+#5499=CARTESIAN_POINT('',(-184.181545770614,-105.68742690406,3.));
+#5500=CARTESIAN_POINT('',(-184.181545770614,-114.68742690406,3.));
+#5501=CARTESIAN_POINT('',(-184.181545770614,-105.999297878237,3.));
+#5502=CARTESIAN_POINT('',(-184.181545770614,-105.68742690406,2.));
+#5503=CARTESIAN_POINT('',(-184.181545770614,-105.68742690406,3.));
+#5504=CARTESIAN_POINT('',(-184.181545770614,-114.68742690406,2.));
+#5505=CARTESIAN_POINT('',(-184.181545770614,-114.68742690406,2.));
+#5506=CARTESIAN_POINT('',(-184.181545770614,-114.68742690406,3.));
+#5507=CARTESIAN_POINT('Origin',(-189.181545770614,-105.68742690406,3.));
+#5508=CARTESIAN_POINT('',(-189.181545770614,-105.68742690406,3.));
+#5509=CARTESIAN_POINT('',(-161.681545770614,-105.68742690406,3.));
+#5510=CARTESIAN_POINT('',(-189.181545770614,-105.68742690406,2.));
+#5511=CARTESIAN_POINT('',(-189.181545770614,-105.68742690406,3.));
+#5512=CARTESIAN_POINT('',(-184.181545770614,-105.68742690406,2.));
+#5513=CARTESIAN_POINT('Origin',(-189.181545770614,-114.68742690406,3.));
+#5514=CARTESIAN_POINT('',(-189.181545770614,-114.68742690406,3.));
+#5515=CARTESIAN_POINT('',(-189.181545770614,-110.499297878237,3.));
+#5516=CARTESIAN_POINT('',(-189.181545770614,-114.68742690406,2.));
+#5517=CARTESIAN_POINT('',(-189.181545770614,-114.68742690406,3.));
+#5518=CARTESIAN_POINT('',(-189.181545770614,-105.68742690406,2.));
+#5519=CARTESIAN_POINT('Origin',(-184.181545770614,-114.68742690406,3.));
+#5520=CARTESIAN_POINT('',(-159.181545770614,-114.68742690406,3.));
+#5521=CARTESIAN_POINT('',(-189.181545770614,-114.68742690406,2.));
+#5522=CARTESIAN_POINT('Origin',(-186.681545770614,-110.18742690406,2.));
+#5523=CARTESIAN_POINT('Origin',(-109.181545770614,-111.187409348464,3.));
+#5524=CARTESIAN_POINT('',(-109.181545770614,-111.187409348464,3.));
+#5525=CARTESIAN_POINT('',(-109.181545770614,-120.187409348464,3.));
+#5526=CARTESIAN_POINT('',(-109.181545770614,-108.749289100439,3.));
+#5527=CARTESIAN_POINT('',(-109.181545770614,-111.187409348464,2.));
+#5528=CARTESIAN_POINT('',(-109.181545770614,-111.187409348464,3.));
+#5529=CARTESIAN_POINT('',(-109.181545770614,-120.187409348464,2.));
+#5530=CARTESIAN_POINT('',(-109.181545770614,-125.188933033705,2.));
+#5531=CARTESIAN_POINT('',(-109.181545770614,-120.187409348464,3.));
+#5532=CARTESIAN_POINT('Origin',(-114.181545770614,-111.187409348464,3.));
+#5533=CARTESIAN_POINT('',(-114.181545770614,-111.187409348464,3.));
+#5534=CARTESIAN_POINT('',(-124.181545770614,-111.187409348464,3.));
+#5535=CARTESIAN_POINT('',(-114.181545770614,-111.187409348464,2.));
+#5536=CARTESIAN_POINT('',(-114.181545770614,-111.187409348464,3.));
+#5537=CARTESIAN_POINT('',(-109.181545770614,-111.187409348464,2.));
+#5538=CARTESIAN_POINT('Origin',(-114.181545770614,-120.187409348464,3.));
+#5539=CARTESIAN_POINT('',(-114.181545770614,-120.187409348464,3.));
+#5540=CARTESIAN_POINT('',(-114.181545770614,-113.249289100439,3.));
+#5541=CARTESIAN_POINT('',(-114.181545770614,-120.187409348464,2.));
+#5542=CARTESIAN_POINT('',(-114.181545770614,-120.187409348464,3.));
+#5543=CARTESIAN_POINT('',(-114.181545770614,-111.187409348464,2.));
+#5544=CARTESIAN_POINT('Origin',(-109.181545770614,-120.187409348464,3.));
+#5545=CARTESIAN_POINT('',(-121.681545770614,-120.187409348464,3.));
+#5546=CARTESIAN_POINT('',(-114.181545770614,-120.187409348464,2.));
+#5547=CARTESIAN_POINT('Origin',(-111.681545770614,-115.687409348464,2.));
+#5548=CARTESIAN_POINT('Origin',(-211.611527548074,-85.8588393103425,9.97183354067129));
+#5549=CARTESIAN_POINT('',(-214.361527548074,-85.8588393103425,9.9718335406713));
+#5550=CARTESIAN_POINT('Origin',(-211.611527548074,-85.8588393103425,9.9718335406713));
+#5551=CARTESIAN_POINT('',(-214.361527548074,-85.8588393103425,-0.0281664593287112));
+#5552=CARTESIAN_POINT('',(-214.361527548074,-85.8588393103425,9.97183354067129));
+#5553=CARTESIAN_POINT('',(-212.714281371378,-83.339626336974,-0.0281664593287123));
+#5554=CARTESIAN_POINT('Origin',(-211.611527548074,-85.8588393103425,-0.0281664593287101));
+#5555=CARTESIAN_POINT('',(-210.50877372477,-83.3396263369739,-0.0281664593287123));
+#5556=CARTESIAN_POINT('Ctrl Pts',(-210.50877372477,-83.3396263369739,-0.0281664593287098));
+#5557=CARTESIAN_POINT('Ctrl Pts',(-210.546480131373,-83.3231208312927,-0.0281664593287097));
+#5558=CARTESIAN_POINT('Ctrl Pts',(-210.584600181147,-83.307443775285,-0.0279624225600793));
+#5559=CARTESIAN_POINT('Ctrl Pts',(-210.943160744825,-83.1693320192223,-0.0247160534556925));
+#5560=CARTESIAN_POINT('Ctrl Pts',(-211.288488771922,-83.1088393103425,-0.0148061720946227));
+#5561=CARTESIAN_POINT('Ctrl Pts',(-211.934566324227,-83.1088393103425,-0.0148061720946227));
+#5562=CARTESIAN_POINT('Ctrl Pts',(-212.279894351324,-83.1693320192223,-0.0247160534556929));
+#5563=CARTESIAN_POINT('Ctrl Pts',(-212.638454915002,-83.307443775285,-0.0279624225600804));
+#5564=CARTESIAN_POINT('Ctrl Pts',(-212.676574964776,-83.3231208312928,-0.0281664593287109));
+#5565=CARTESIAN_POINT('Ctrl Pts',(-212.714281371378,-83.339626336974,-0.0281664593287098));
+#5566=CARTESIAN_POINT('Origin',(-211.611527548074,-85.8588393103425,-0.0281664593287101));
+#5567=CARTESIAN_POINT('Origin',(-211.670129185533,-108.858839310342,9.9718335406713));
+#5568=CARTESIAN_POINT('',(-214.420129185533,-108.858839310342,9.9718335406713));
+#5569=CARTESIAN_POINT('Origin',(-211.670129185533,-108.858839310342,9.9718335406713));
+#5570=CARTESIAN_POINT('',(-214.420129185533,-108.858839310342,-0.0281664593287112));
+#5571=CARTESIAN_POINT('',(-214.420129185533,-108.858839310342,9.9718335406713));
+#5572=CARTESIAN_POINT('',(-210.483454955385,-111.339626336974,-0.0281664593287013));
+#5573=CARTESIAN_POINT('Origin',(-211.670129185533,-108.858839310342,-0.0281664593287112));
+#5574=CARTESIAN_POINT('',(-212.856803415681,-111.339626336974,-0.0281664593287013));
+#5575=CARTESIAN_POINT('Ctrl Pts',(-212.856803415681,-111.339626336974,-0.0281664593287018));
+#5576=CARTESIAN_POINT('Ctrl Pts',(-212.795236685399,-111.369076528173,-0.0281664593287019));
+#5577=CARTESIAN_POINT('Ctrl Pts',(-212.732405824487,-111.396309413517,-0.0275178049960072));
+#5578=CARTESIAN_POINT('Ctrl Pts',(-212.345686103685,-111.547007213812,-0.0213689262165566));
+#5579=CARTESIAN_POINT('Ctrl Pts',(-211.996796777474,-111.608839310342,-0.00996472730908665));
+#5580=CARTESIAN_POINT('Ctrl Pts',(-211.343461593592,-111.608839310342,-0.00996472730908665));
+#5581=CARTESIAN_POINT('Ctrl Pts',(-210.994572267381,-111.547007213812,-0.0213689262165576));
+#5582=CARTESIAN_POINT('Ctrl Pts',(-210.607852546579,-111.396309413517,-0.0275178049960077));
+#5583=CARTESIAN_POINT('Ctrl Pts',(-210.545021685667,-111.369076528173,-0.0281664593287017));
+#5584=CARTESIAN_POINT('Ctrl Pts',(-210.483454955385,-111.339626336974,-0.0281664593287018));
+#5585=CARTESIAN_POINT('Origin',(-211.670129185533,-108.858839310342,-0.0281664593287112));
+#5586=CARTESIAN_POINT('Origin',(-204.181545770614,-81.3396263369739,-0.0281664593287104));
+#5587=CARTESIAN_POINT('',(-206.018379808514,-83.3396263369739,-0.0281664593287098));
+#5588=CARTESIAN_POINT('',(-204.181545770614,-83.3396263369739,-0.0281664593287098));
+#5589=CARTESIAN_POINT('',(-204.181545770615,-82.8929856495304,-0.0281664593287099));
+#5590=CARTESIAN_POINT('Ctrl Pts',(-204.181567875676,-82.8929429545345,-0.0281664593287061));
+#5591=CARTESIAN_POINT('Ctrl Pts',(-204.254347713889,-82.9306242495359,-0.0281664593287056));
+#5592=CARTESIAN_POINT('Ctrl Pts',(-204.578247409045,-83.0858597215967,-0.0281664593287035));
+#5593=CARTESIAN_POINT('Ctrl Pts',(-205.054701905816,-83.2389373741377,-0.0281664593286989));
+#5594=CARTESIAN_POINT('Ctrl Pts',(-205.534240192166,-83.3144643337345,-0.0281664593286971));
+#5595=CARTESIAN_POINT('Ctrl Pts',(-205.810597028159,-83.3360062694659,-0.0281664593287087));
+#5596=CARTESIAN_POINT('Ctrl Pts',(-205.949113581501,-83.3396263369727,-0.0281664593287031));
+#5597=CARTESIAN_POINT('Ctrl Pts',(-206.018379808491,-83.3396263369739,-0.0281664593287026));
+#5598=CARTESIAN_POINT('',(-204.181545770615,-111.875410224955,-0.0281664593287022));
+#5599=CARTESIAN_POINT('',(-204.181545770614,-81.3396263369739,-0.0281664593287104));
+#5600=CARTESIAN_POINT('',(-206.181446600706,-111.339626336974,-0.0281664593287023));
+#5601=CARTESIAN_POINT('Ctrl Pts',(-206.181446600706,-111.339626336974,-0.0281664593287023));
+#5602=CARTESIAN_POINT('Ctrl Pts',(-206.112197291704,-111.339626336974,-0.0281664593287023));
+#5603=CARTESIAN_POINT('Ctrl Pts',(-205.973698580479,-111.343224755802,-0.0281664593287023));
+#5604=CARTESIAN_POINT('Ctrl Pts',(-205.697426378589,-111.364784096519,-0.0281664593287023));
+#5605=CARTESIAN_POINT('Ctrl Pts',(-205.354867821539,-111.418599929817,-0.0281664593287023));
+#5606=CARTESIAN_POINT('Ctrl Pts',(-204.885740686274,-111.543215575215,-0.0281664593287023));
+#5607=CARTESIAN_POINT('Ctrl Pts',(-204.494982925564,-111.703625353628,-0.0281664593287022));
+#5608=CARTESIAN_POINT('Ctrl Pts',(-204.246345213453,-111.83799726872,-0.0281664593287022));
+#5609=CARTESIAN_POINT('Ctrl Pts',(-204.181541644499,-111.875403077207,-0.0281664593287022));
+#5610=CARTESIAN_POINT('',(-204.181545770614,-111.339626336974,-0.0281664593287023));
+#5611=CARTESIAN_POINT('',(-217.181545770614,-111.339626336974,-0.0281664593287023));
+#5612=CARTESIAN_POINT('',(-204.181545770614,-111.339626336974,-0.0281664593287023));
+#5613=CARTESIAN_POINT('',(-217.181545770614,-83.3396263369739,-0.0281664593287098));
+#5614=CARTESIAN_POINT('',(-217.181545770614,-89.3396263369739,-0.0281664593287081));
+#5615=CARTESIAN_POINT('',(-204.181545770614,-83.3396263369739,-0.0281664593287098));
+#5616=CARTESIAN_POINT('Origin',(-146.681545770614,-144.311168852415,13.5));
+#5617=CARTESIAN_POINT('',(-138.314945505273,-141.311168852415,15.));
+#5618=CARTESIAN_POINT('',(-138.314945505273,-144.311168852415,15.));
+#5619=CARTESIAN_POINT('',(-138.314945505273,-144.311168852415,15.));
+#5620=CARTESIAN_POINT('',(-155.048146035955,-141.311168852415,15.));
+#5621=CARTESIAN_POINT('Origin',(-146.681545770614,-141.311168852415,13.5));
+#5622=CARTESIAN_POINT('',(-155.048146035955,-144.311168852415,15.));
+#5623=CARTESIAN_POINT('',(-155.048146035955,-144.311168852415,15.));
+#5624=CARTESIAN_POINT('Origin',(-146.681545770614,-144.311168852415,13.5));
+#5625=CARTESIAN_POINT('Origin',(-121.681545770614,-144.311168852415,13.5));
+#5626=CARTESIAN_POINT('',(-130.048146035955,-144.311168852415,15.));
+#5627=CARTESIAN_POINT('',(-130.048146035955,-141.311168852415,15.));
+#5628=CARTESIAN_POINT('',(-130.048146035955,-144.311168852415,15.));
+#5629=CARTESIAN_POINT('',(-113.314945505273,-144.311168852415,15.));
+#5630=CARTESIAN_POINT('Origin',(-121.681545770614,-144.311168852415,13.5));
+#5631=CARTESIAN_POINT('',(-113.314945505273,-141.311168852415,15.));
+#5632=CARTESIAN_POINT('',(-113.314945505273,-144.311168852415,15.));
+#5633=CARTESIAN_POINT('Origin',(-121.681545770614,-141.311168852415,13.5));
+#5634=CARTESIAN_POINT('Origin',(-134.181545770614,-106.311168852415,15.));
+#5635=CARTESIAN_POINT('',(-158.181545770614,-141.311168852415,15.));
+#5636=CARTESIAN_POINT('',(-147.681545770614,-141.311168852415,15.));
+#5637=CARTESIAN_POINT('',(-158.181545770614,-136.628519700765,15.));
+#5638=CARTESIAN_POINT('',(-158.181545770614,-122.763467838619,15.));
+#5639=CARTESIAN_POINT('',(-195.571953037155,-126.982317151194,15.));
+#5640=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,15.));
+#5641=CARTESIAN_POINT('',(-201.181545770614,-118.704731035464,15.));
+#5642=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,15.));
+#5643=CARTESIAN_POINT('',(-201.181545770614,-81.3111688524149,15.));
+#5644=CARTESIAN_POINT('',(-201.181545770614,-93.8111688524148,15.));
+#5645=CARTESIAN_POINT('',(-201.172302818316,-80.9515636522235,15.));
+#5646=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,15.));
+#5647=CARTESIAN_POINT('',(-193.686069654732,-74.3287263414743,15.));
+#5648=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,15.));
+#5649=CARTESIAN_POINT('',(-191.911275500344,-74.6895472307933,15.));
+#5650=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,15.));
+#5651=CARTESIAN_POINT('',(-76.4518160408844,-74.6895472307933,15.));
+#5652=CARTESIAN_POINT('Origin',(-134.181545770614,93.6888311475868,15.));
+#5653=CARTESIAN_POINT('',(-74.6770218864968,-74.3287263414744,15.));
+#5654=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,15.));
+#5655=CARTESIAN_POINT('',(-67.1907887229121,-80.9515636522234,15.));
+#5656=CARTESIAN_POINT('Origin',(-70.8321482282875,-77.5251222106383,15.));
+#5657=CARTESIAN_POINT('',(-67.1815457706142,-81.3111688524149,15.));
+#5658=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,15.));
+#5659=CARTESIAN_POINT('',(-67.1815457706141,-118.704731035464,15.));
+#5660=CARTESIAN_POINT('',(-67.1815457706141,-113.163299597112,15.));
+#5661=CARTESIAN_POINT('',(-72.7911385040727,-126.982317151194,15.));
+#5662=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,15.));
+#5663=CARTESIAN_POINT('',(-110.181545770614,-136.628519700765,15.));
+#5664=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,15.));
+#5665=CARTESIAN_POINT('',(-110.181545770614,-141.311168852415,15.));
+#5666=CARTESIAN_POINT('',(-110.181545770614,-125.311168852415,15.));
+#5667=CARTESIAN_POINT('',(-147.681545770614,-141.311168852415,15.));
+#5668=CARTESIAN_POINT('',(-109.181545770614,-144.311168852415,15.));
+#5669=CARTESIAN_POINT('',(-161.181545770614,-144.311168852415,15.));
+#5670=CARTESIAN_POINT('',(-107.181545770614,-142.311168852415,15.));
+#5671=CARTESIAN_POINT('Origin',(-109.181545770614,-142.311168852415,15.));
+#5672=CARTESIAN_POINT('',(-107.181545770614,-140.919301538152,15.));
+#5673=CARTESIAN_POINT('',(-107.181545770614,-144.311168852415,15.));
+#5674=CARTESIAN_POINT('',(-105.509229386433,-138.946328287466,15.));
+#5675=CARTESIAN_POINT('Origin',(-105.181545770614,-140.919301538152,15.));
+#5676=CARTESIAN_POINT('',(-70.5451821342505,-129.330840129045,15.));
+#5677=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,15.));
+#5678=CARTESIAN_POINT('',(-65.9243175321664,-125.656191089986,15.));
+#5679=CARTESIAN_POINT('Origin',(-74.1815457706141,-120.015430341809,15.));
+#5680=CARTESIAN_POINT('',(-65.8550730591838,-125.553467194865,15.));
+#5681=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,15.));
+#5682=CARTESIAN_POINT('',(-64.1815457706141,-120.015430341809,15.));
+#5683=CARTESIAN_POINT('Origin',(-74.1815457706141,-120.015430341809,15.));
+#5684=CARTESIAN_POINT('',(-64.1815457706142,-81.3111688524149,15.));
+#5685=CARTESIAN_POINT('',(-64.1815457706141,-120.015430341809,15.));
+#5686=CARTESIAN_POINT('',(-77.4247890138573,-71.8517093929555,15.));
+#5687=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,15.));
+#5688=CARTESIAN_POINT('',(-190.938302527371,-71.8517093929555,15.));
+#5689=CARTESIAN_POINT('Origin',(-134.181545770614,93.6888311475868,15.));
+#5690=CARTESIAN_POINT('',(-199.993927707805,-73.1738341403474,15.));
+#5691=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,15.));
+#5692=CARTESIAN_POINT('',(-201.549446967915,-74.5499535809703,15.));
+#5693=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,15.));
+#5694=CARTESIAN_POINT('',(-204.181545770614,-81.3111688524149,15.));
+#5695=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,15.));
+#5696=CARTESIAN_POINT('',(-204.181545770614,-120.015430341809,15.));
+#5697=CARTESIAN_POINT('',(-204.181545770614,-81.3111688524149,15.));
+#5698=CARTESIAN_POINT('',(-202.508018482043,-125.553467194868,15.));
+#5699=CARTESIAN_POINT('Origin',(-194.181545770614,-120.015430341809,15.));
+#5700=CARTESIAN_POINT('',(-202.438774009064,-125.656191089984,15.));
+#5701=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,15.));
+#5702=CARTESIAN_POINT('',(-197.817909406978,-129.330840129045,15.));
+#5703=CARTESIAN_POINT('Origin',(-194.181545770614,-120.015430341809,15.));
+#5704=CARTESIAN_POINT('',(-162.853862154795,-138.946328287466,15.));
+#5705=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,15.));
+#5706=CARTESIAN_POINT('',(-161.181545770614,-140.919301538152,15.));
+#5707=CARTESIAN_POINT('Origin',(-163.181545770614,-140.919301538152,15.));
+#5708=CARTESIAN_POINT('',(-161.181545770614,-142.311168852415,15.));
+#5709=CARTESIAN_POINT('',(-161.181545770614,-139.215766824823,15.));
+#5710=CARTESIAN_POINT('',(-159.181545770614,-144.311168852415,15.));
+#5711=CARTESIAN_POINT('Origin',(-159.181545770614,-142.311168852415,15.));
+#5712=CARTESIAN_POINT('',(-161.181545770614,-144.311168852415,15.));
+#5713=CARTESIAN_POINT('',(-200.280943312941,-77.5251222106383,15.));
+#5714=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,15.));
+#5715=CARTESIAN_POINT('',(-72.7853819140103,-122.810290591316,15.));
+#5716=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,15.));
+#5717=CARTESIAN_POINT('',(-201.077709627218,-122.810290591316,15.));
+#5718=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,15.));
+#5719=CARTESIAN_POINT('',(-73.5821482282874,-77.5251222106383,15.));
+#5720=CARTESIAN_POINT('Origin',(-70.8321482282874,-77.5251222106383,15.));
+#5721=CARTESIAN_POINT('Origin',(-161.181545770614,-144.311168852415,0.));
+#5722=CARTESIAN_POINT('',(-159.181545770614,-144.311168852415,2.));
+#5723=CARTESIAN_POINT('',(-159.181545770614,-144.311168852415,0.));
+#5724=CARTESIAN_POINT('',(-109.181545770614,-144.311168852415,2.));
+#5725=CARTESIAN_POINT('',(-147.681545770614,-144.311168852415,2.));
+#5726=CARTESIAN_POINT('',(-109.181545770614,-144.311168852415,0.));
+#5727=CARTESIAN_POINT('',(-161.181545770614,-144.311168852415,15.));
+#5728=CARTESIAN_POINT('Origin',(-217.181545770614,-111.339626336974,1.9718335406713));
+#5729=CARTESIAN_POINT('',(-219.181545770614,-111.339626336974,1.9718335406713));
+#5730=CARTESIAN_POINT('Origin',(-217.181545770614,-111.339626336974,1.9718335406713));
+#5731=CARTESIAN_POINT('',(-217.181545770614,-113.339626336974,1.9718335406713));
+#5732=CARTESIAN_POINT('Origin',(-217.181545770614,-111.339626336974,1.9718335406713));
+#5733=CARTESIAN_POINT('Origin',(-217.181545770614,-111.339626336974,1.9718335406713));
+#5734=CARTESIAN_POINT('Origin',(-204.181545770614,-111.339626336974,1.9718335406713));
+#5735=CARTESIAN_POINT('',(-206.181446600706,-113.339626336974,1.9718335406713));
+#5736=CARTESIAN_POINT('Origin',(-206.181446600706,-111.339626336974,1.9718335406713));
+#5737=CARTESIAN_POINT('',(-204.181545770614,-113.339626336974,1.9718335406713));
+#5738=CARTESIAN_POINT('Ctrl Pts',(-206.181446600706,-111.339626336974,-0.0281664593287023));
+#5739=CARTESIAN_POINT('Ctrl Pts',(-206.112197291704,-111.339626336974,-0.0281664593287023));
+#5740=CARTESIAN_POINT('Ctrl Pts',(-205.973698580479,-111.343224755802,-0.0281664593287023));
+#5741=CARTESIAN_POINT('Ctrl Pts',(-205.697426378589,-111.364784096519,-0.0281664593287023));
+#5742=CARTESIAN_POINT('Ctrl Pts',(-205.354867821539,-111.418599929817,-0.0281664593287023));
+#5743=CARTESIAN_POINT('Ctrl Pts',(-204.885740686274,-111.543215575215,-0.0281664593287023));
+#5744=CARTESIAN_POINT('Ctrl Pts',(-204.371653633609,-111.754253201322,-0.0281664593287022));
+#5745=CARTESIAN_POINT('Ctrl Pts',(-203.896761893625,-112.042312246519,-0.0281664593287021));
+#5746=CARTESIAN_POINT('Ctrl Pts',(-203.571820056898,-112.302426342923,-0.028166459328702));
+#5747=CARTESIAN_POINT('Ctrl Pts',(-203.394810018377,-112.468295655607,-0.028166459328702));
+#5748=CARTESIAN_POINT('Ctrl Pts',(-203.297538262178,-112.56685182366,-0.028166459328702));
+#5749=CARTESIAN_POINT('Ctrl Pts',(-203.18713817142,-112.684584850752,-0.0281664593287019));
+#5750=CARTESIAN_POINT('Ctrl Pts',(-202.985595677311,-112.921603743522,-0.0281664593287019));
+#5751=CARTESIAN_POINT('Ctrl Pts',(-202.671612818737,-113.376430547654,-0.0281664593287018));
+#5752=CARTESIAN_POINT('Ctrl Pts',(-202.447724667547,-113.868302068723,-0.0281664593287016));
+#5753=CARTESIAN_POINT('Ctrl Pts',(-202.325758237439,-114.258985006422,-0.0281664593287016));
+#5754=CARTESIAN_POINT('Ctrl Pts',(-202.280920740934,-114.432952255467,-0.0281664593287015));
+#5755=CARTESIAN_POINT('Ctrl Pts',(-202.253356279393,-114.556683995409,-0.0281664593287015));
+#5756=CARTESIAN_POINT('Ctrl Pts',(-202.232699230786,-114.657278924374,-0.0281664593287015));
+#5757=CARTESIAN_POINT('Ctrl Pts',(-202.215811808864,-114.746511948139,-0.0281664593287015));
+#5758=CARTESIAN_POINT('Ctrl Pts',(-202.207102982031,-114.789685023023,-0.0281664593287015));
+#5759=CARTESIAN_POINT('Ctrl Pts',(-202.201361131382,-114.816921064766,-0.0281664593287015));
+#5760=CARTESIAN_POINT('Ctrl Pts',(-202.194994265556,-114.84205761566,-0.0281664593287015));
+#5761=CARTESIAN_POINT('Ctrl Pts',(-202.190924548962,-114.853691611957,-0.0281664593287015));
+#5762=CARTESIAN_POINT('Ctrl Pts',(-202.188809957058,-114.858211982044,-0.0281664593287015));
+#5763=CARTESIAN_POINT('Ctrl Pts',(-202.187120212385,-114.861909679894,-0.0281664593287015));
+#5764=CARTESIAN_POINT('Ctrl Pts',(-202.184906135655,-114.864100329101,-0.0281664593287015));
+#5765=CARTESIAN_POINT('Ctrl Pts',(-206.181446600706,-111.938024937658,-0.0281664593287023));
+#5766=CARTESIAN_POINT('Ctrl Pts',(-206.122602690585,-111.937977463417,-0.028164516208525));
+#5767=CARTESIAN_POINT('Ctrl Pts',(-206.004793644024,-111.940960049672,-0.0281704061401611));
+#5768=CARTESIAN_POINT('Ctrl Pts',(-205.769895220881,-111.959087876279,-0.0281735850120563));
+#5769=CARTESIAN_POINT('Ctrl Pts',(-205.478477186167,-112.004557807593,-0.0281802638585951));
+#5770=CARTESIAN_POINT('Ctrl Pts',(-205.079255289322,-112.110061802777,-0.0282167664966937));
+#5771=CARTESIAN_POINT('Ctrl Pts',(-204.641509946991,-112.288787752932,-0.0282272542241123));
+#5772=CARTESIAN_POINT('Ctrl Pts',(-204.236707770816,-112.532824771794,-0.0283061074565235));
+#5773=CARTESIAN_POINT('Ctrl Pts',(-203.958971233423,-112.753210257538,-0.0284111952103964));
+#5774=CARTESIAN_POINT('Ctrl Pts',(-203.807448308765,-112.893568626078,-0.0284089490796597));
+#5775=CARTESIAN_POINT('Ctrl Pts',(-203.724042411487,-112.97695061906,-0.0283893203240815));
+#5776=CARTESIAN_POINT('Ctrl Pts',(-203.629216358589,-113.0765765005,-0.0284424945507927));
+#5777=CARTESIAN_POINT('Ctrl Pts',(-203.455896808138,-113.27704372491,-0.0283732315474192));
+#5778=CARTESIAN_POINT('Ctrl Pts',(-203.181771629451,-113.661866405069,-0.0295642192878182));
+#5779=CARTESIAN_POINT('Ctrl Pts',(-202.980487020667,-114.076965121218,-0.0308079242655842));
+#5780=CARTESIAN_POINT('Ctrl Pts',(-202.838427000384,-114.404504133483,-0.0308427235438797));
+#5781=CARTESIAN_POINT('Ctrl Pts',(-202.768654276599,-114.549851579458,-0.0303464320881426));
+#5782=CARTESIAN_POINT('Ctrl Pts',(-202.705329758847,-114.653034918733,-0.0299976712351466));
+#5783=CARTESIAN_POINT('Ctrl Pts',(-202.642938818211,-114.73680324242,-0.0292586575455471));
+#5784=CARTESIAN_POINT('Ctrl Pts',(-202.55537110625,-114.811193914702,-0.02877476809736));
+#5785=CARTESIAN_POINT('Ctrl Pts',(-202.486695115546,-114.847256245333,-0.0284535420019913));
+#5786=CARTESIAN_POINT('Ctrl Pts',(-202.436151297732,-114.870027968259,-0.0282802701927985));
+#5787=CARTESIAN_POINT('Ctrl Pts',(-202.365488787963,-114.891093968006,-0.0281951837692611));
+#5788=CARTESIAN_POINT('Ctrl Pts',(-202.313083573915,-114.900859773878,-0.0281763286519544));
+#5789=CARTESIAN_POINT('Ctrl Pts',(-202.284580950522,-114.904655411076,-0.0281703964454168));
+#5790=CARTESIAN_POINT('Ctrl Pts',(-202.26152335839,-114.907761509058,-0.0281676508565471));
+#5791=CARTESIAN_POINT('Ctrl Pts',(-202.229926668741,-114.90960232658,-0.0281664593287015));
+#5792=CARTESIAN_POINT('Ctrl Pts',(-206.181446600706,-112.973944473346,0.474049685853977));
+#5793=CARTESIAN_POINT('Ctrl Pts',(-206.140474547024,-112.97382145196,0.473966587123157));
+#5794=CARTESIAN_POINT('Ctrl Pts',(-206.058555452986,-112.975683606025,0.473794001599411));
+#5795=CARTESIAN_POINT('Ctrl Pts',(-205.895043261513,-112.987858545352,0.473407380202495));
+#5796=CARTESIAN_POINT('Ctrl Pts',(-205.692204314654,-113.018859713952,0.47284223879847));
+#5797=CARTESIAN_POINT('Ctrl Pts',(-205.414071202539,-113.091170022362,0.471845933337101));
+#5798=CARTESIAN_POINT('Ctrl Pts',(-205.108609313167,-113.21404901404,0.470303798712571));
+#5799=CARTESIAN_POINT('Ctrl Pts',(-204.824975138307,-113.381908281971,0.467965067801065));
+#5800=CARTESIAN_POINT('Ctrl Pts',(-204.629324379058,-113.533350020596,0.465317003335046));
+#5801=CARTESIAN_POINT('Ctrl Pts',(-204.521707317052,-113.629864779508,0.463227298276206));
+#5802=CARTESIAN_POINT('Ctrl Pts',(-204.462254400683,-113.687172635127,0.461860685316225));
+#5803=CARTESIAN_POINT('Ctrl Pts',(-204.394284161847,-113.755584189394,0.46003890348845));
+#5804=CARTESIAN_POINT('Ctrl Pts',(-204.269868272006,-113.893180881345,0.456274813604888));
+#5805=CARTESIAN_POINT('Ctrl Pts',(-204.063979334616,-114.156227951278,0.443848194623846));
+#5806=CARTESIAN_POINT('Ctrl Pts',(-203.901614017824,-114.438000651262,0.423508142060349));
+#5807=CARTESIAN_POINT('Ctrl Pts',(-203.726727315122,-114.656895607053,0.363183717442606));
+#5808=CARTESIAN_POINT('Ctrl Pts',(-203.615628796626,-114.753022868598,0.316155332947462));
+#5809=CARTESIAN_POINT('Ctrl Pts',(-203.49165228318,-114.820754643077,0.262759986559253));
+#5810=CARTESIAN_POINT('Ctrl Pts',(-203.358386562822,-114.875573061373,0.206321250972572));
+#5811=CARTESIAN_POINT('Ctrl Pts',(-203.148625393729,-114.924210745304,0.128874701833108));
+#5812=CARTESIAN_POINT('Ctrl Pts',(-202.9755817151,-114.947931523455,0.0798121147726386));
+#5813=CARTESIAN_POINT('Ctrl Pts',(-202.846919835853,-114.962941946997,0.0466931433584825));
+#5814=CARTESIAN_POINT('Ctrl Pts',(-202.663837931377,-114.976902193981,0.01134126120518));
+#5815=CARTESIAN_POINT('Ctrl Pts',(-202.526857403724,-114.983402211313,-0.0064182014872613));
+#5816=CARTESIAN_POINT('Ctrl Pts',(-202.452179167848,-114.985930639432,-0.01342796110377));
+#5817=CARTESIAN_POINT('Ctrl Pts',(-202.391728372083,-114.988001839384,-0.0192639563819193));
+#5818=CARTESIAN_POINT('Ctrl Pts',(-202.308712489688,-114.989230709016,-0.0227843053142946));
+#5819=CARTESIAN_POINT('Ctrl Pts',(-206.181446600706,-113.339626336974,1.52303459015847));
+#5820=CARTESIAN_POINT('Ctrl Pts',(-206.146846822521,-113.339571145213,1.52282505267345));
+#5821=CARTESIAN_POINT('Ctrl Pts',(-206.077574262023,-113.341266696773,1.52238644123261));
+#5822=CARTESIAN_POINT('Ctrl Pts',(-205.939436125319,-113.351797815154,1.52140674958801));
+#5823=CARTESIAN_POINT('Ctrl Pts',(-205.768030971522,-113.378349175035,1.51997438443633));
+#5824=CARTESIAN_POINT('Ctrl Pts',(-205.533133010511,-113.440074319647,1.51743601189823));
+#5825=CARTESIAN_POINT('Ctrl Pts',(-205.275409538023,-113.54472656175,1.51352489499133));
+#5826=CARTESIAN_POINT('Ctrl Pts',(-205.036722206374,-113.687651983846,1.5075490447059));
+#5827=CARTESIAN_POINT('Ctrl Pts',(-204.872560878133,-113.816697505919,1.5007690119622));
+#5828=CARTESIAN_POINT('Ctrl Pts',(-204.782726493516,-113.898862574014,1.4954332219384));
+#5829=CARTESIAN_POINT('Ctrl Pts',(-204.733212152987,-113.947664826936,1.49196010204889));
+#5830=CARTESIAN_POINT('Ctrl Pts',(-204.676719631967,-114.005964816137,1.48725008255218));
+#5831=CARTESIAN_POINT('Ctrl Pts',(-204.573816387019,-114.123246596752,1.47783342265309));
+#5832=CARTESIAN_POINT('Ctrl Pts',(-204.405707179155,-114.348160629957,1.44453320025181));
+#5833=CARTESIAN_POINT('Ctrl Pts',(-204.282210180731,-114.590160170402,1.39291694261933));
+#5834=CARTESIAN_POINT('Ctrl Pts',(-204.156222954412,-114.779723173524,1.22966268652761));
+#5835=CARTESIAN_POINT('Ctrl Pts',(-204.07357005186,-114.863390131855,1.09888745891008));
+#5836=CARTESIAN_POINT('Ctrl Pts',(-203.967454437511,-114.922484589801,0.94272157389387));
+#5837=CARTESIAN_POINT('Ctrl Pts',(-203.84477052733,-114.970291912989,0.773941492121666));
+#5838=CARTESIAN_POINT('Ctrl Pts',(-203.613539813369,-115.012527078204,0.525799068204155));
+#5839=CARTESIAN_POINT('Ctrl Pts',(-203.388782165257,-115.032950235796,0.359143355215163));
+#5840=CARTESIAN_POINT('Ctrl Pts',(-203.214661976226,-115.045840520017,0.244652633240547));
+#5841=CARTESIAN_POINT('Ctrl Pts',(-202.946295270488,-115.057753626606,0.117939627278191));
+#5842=CARTESIAN_POINT('Ctrl Pts',(-202.733933520213,-115.063275034248,0.0526579728636904));
+#5843=CARTESIAN_POINT('Ctrl Pts',(-202.616175000883,-115.065420871552,0.0267774376267234));
+#5844=CARTESIAN_POINT('Ctrl Pts',(-202.520469903196,-115.067176827499,0.0051122849907378));
+#5845=CARTESIAN_POINT('Ctrl Pts',(-202.38686345478,-115.06821744624,-0.00802861711658657));
+#5846=CARTESIAN_POINT('Ctrl Pts',(-206.181446600706,-113.339626336974,1.9718335406713));
+#5847=CARTESIAN_POINT('Ctrl Pts',(-206.146820229364,-113.339626336974,1.97158973323535));
+#5848=CARTESIAN_POINT('Ctrl Pts',(-206.077567280521,-113.341425546388,1.97107616333618));
+#5849=CARTESIAN_POINT('Ctrl Pts',(-205.939422367889,-113.352205216747,1.96993215957611));
+#5850=CARTESIAN_POINT('Ctrl Pts',(-205.768129873933,-113.379113133395,1.96825859287479));
+#5851=CARTESIAN_POINT('Ctrl Pts',(-205.533537864338,-113.441420956094,1.96528439254103));
+#5852=CARTESIAN_POINT('Ctrl Pts',(-205.276448208836,-113.546939769148,1.96071459199766));
+#5853=CARTESIAN_POINT('Ctrl Pts',(-205.038900543477,-113.690969291746,1.95370746136295));
+#5854=CARTESIAN_POINT('Ctrl Pts',(-204.87630305916,-113.821026339949,1.94574870072859));
+#5855=CARTESIAN_POINT('Ctrl Pts',(-204.787647753138,-113.90396099629,1.93949953517666));
+#5856=CARTESIAN_POINT('Ctrl Pts',(-204.738936990757,-113.953239080317,1.9354411392178));
+#5857=CARTESIAN_POINT('Ctrl Pts',(-204.683519054854,-114.012105593863,1.92989073448492));
+#5858=CARTESIAN_POINT('Ctrl Pts',(-204.582982544804,-114.130615040248,1.9189800522226));
+#5859=CARTESIAN_POINT('Ctrl Pts',(-204.422359277988,-114.358028442314,1.87906267989088));
+#5860=CARTESIAN_POINT('Ctrl Pts',(-204.312705307154,-114.603964202848,1.81895624960821));
+#5861=CARTESIAN_POINT('Ctrl Pts',(-204.223077955975,-114.799305671698,1.62205587405213));
+#5862=CARTESIAN_POINT('Ctrl Pts',(-204.167348409194,-114.886289296221,1.46213163673794));
+#5863=CARTESIAN_POINT('Ctrl Pts',(-204.086889106529,-114.948155166191,1.26636915452548));
+#5864=CARTESIAN_POINT('Ctrl Pts',(-203.988437354593,-114.998452630674,1.05250812849707));
+#5865=CARTESIAN_POINT('Ctrl Pts',(-203.774756122102,-115.043069142556,0.727970173612876));
+#5866=CARTESIAN_POINT('Ctrl Pts',(-203.54296623662,-115.064655679998,0.504202813609458));
+#5867=CARTESIAN_POINT('Ctrl Pts',(-203.358937132067,-115.07827370087,0.34929934072887));
+#5868=CARTESIAN_POINT('Ctrl Pts',(-203.062330075051,-115.090841976317,0.17521329552996));
+#5869=CARTESIAN_POINT('Ctrl Pts',(-202.820555120909,-115.096658974465,0.0845691198511559));
+#5870=CARTESIAN_POINT('Ctrl Pts',(-202.685310300992,-115.098919159509,0.0485680361841242));
+#5871=CARTESIAN_POINT('Ctrl Pts',(-202.575176289284,-115.100768008434,0.0183627511748311));
+#5872=CARTESIAN_POINT('Ctrl Pts',(-202.420153328715,-115.101863333038,-5.60662627435704E-14));
+#5873=CARTESIAN_POINT('',(-203.847072321916,-112.513393250479,0.));
+#5874=CARTESIAN_POINT('',(-202.420153328717,-115.101863333037,1.19071419391048E-13));
+#5875=CARTESIAN_POINT('Ctrl Pts',(-203.847072321916,-112.513393250479,-2.4975232381688E-17));
+#5876=CARTESIAN_POINT('Ctrl Pts',(-203.638266541808,-112.685811644161,-2.49756870565371E-17));
+#5877=CARTESIAN_POINT('Ctrl Pts',(-203.448705418706,-112.881232262806,-6.78596068226511E-12));
+#5878=CARTESIAN_POINT('Ctrl Pts',(-203.089659963845,-113.344939836588,-6.78596068226511E-12));
+#5879=CARTESIAN_POINT('Ctrl Pts',(-202.844629784759,-113.722936222622,2.92264912087919E-13));
+#5880=CARTESIAN_POINT('Ctrl Pts',(-202.653159984933,-114.334087806806,2.92266397645678E-13));
+#5881=CARTESIAN_POINT('Ctrl Pts',(-202.631715245052,-114.410975933372,-8.1601392309949E-14));
+#5882=CARTESIAN_POINT('Ctrl Pts',(-202.598621789875,-114.544657557599,-8.1601392309949E-14));
+#5883=CARTESIAN_POINT('Ctrl Pts',(-202.586341525368,-114.599094544519,-1.41553435639707E-14));
+#5884=CARTESIAN_POINT('Ctrl Pts',(-202.564404152599,-114.704363784686,-1.41553435639707E-14));
+#5885=CARTESIAN_POINT('Ctrl Pts',(-202.552179648216,-114.767855019364,4.44043372105397E-15));
+#5886=CARTESIAN_POINT('Ctrl Pts',(-202.540736624899,-114.827042924262,4.44142811552183E-15));
+#5887=CARTESIAN_POINT('Ctrl Pts',(-202.533738324219,-114.862928764413,-2.99760216648792E-14));
+#5888=CARTESIAN_POINT('Ctrl Pts',(-202.519780009813,-114.923670249771,-2.99760216648792E-14));
+#5889=CARTESIAN_POINT('Ctrl Pts',(-202.511488507316,-114.953155330512,2.99762716473407E-10));
+#5890=CARTESIAN_POINT('Ctrl Pts',(-202.490399173619,-115.00443720331,2.99762713228414E-10));
+#5891=CARTESIAN_POINT('Ctrl Pts',(-202.47933082808,-115.02567030897,-2.61735078055381E-13));
+#5892=CARTESIAN_POINT('Ctrl Pts',(-202.452682533954,-115.066089646933,-2.61735078055381E-13));
+#5893=CARTESIAN_POINT('Ctrl Pts',(-202.437361173807,-115.084837567088,0.));
+#5894=CARTESIAN_POINT('Ctrl Pts',(-202.420153328715,-115.101863333038,0.));
+#5895=CARTESIAN_POINT('Ctrl Pts',(-202.420153328715,-115.101863333038,-5.60662627435704E-14));
+#5896=CARTESIAN_POINT('Ctrl Pts',(-202.575176289284,-115.100768008434,0.0183627511748311));
+#5897=CARTESIAN_POINT('Ctrl Pts',(-202.685310300992,-115.098919159509,0.0485680361841242));
+#5898=CARTESIAN_POINT('Ctrl Pts',(-202.820555120909,-115.096658974465,0.0845691198511559));
+#5899=CARTESIAN_POINT('Ctrl Pts',(-203.062330075051,-115.090841976317,0.17521329552996));
+#5900=CARTESIAN_POINT('Ctrl Pts',(-203.358937132067,-115.07827370087,0.34929934072887));
+#5901=CARTESIAN_POINT('Ctrl Pts',(-203.54296623662,-115.064655679998,0.504202813609458));
+#5902=CARTESIAN_POINT('Ctrl Pts',(-203.774756122102,-115.043069142556,0.727970173612876));
+#5903=CARTESIAN_POINT('Ctrl Pts',(-203.988437354593,-114.998452630674,1.05250812849707));
+#5904=CARTESIAN_POINT('Ctrl Pts',(-204.086889106529,-114.948155166191,1.26636915452548));
+#5905=CARTESIAN_POINT('Ctrl Pts',(-204.167348409194,-114.886289296221,1.46213163673794));
+#5906=CARTESIAN_POINT('Ctrl Pts',(-204.223077955975,-114.799305671698,1.62205587405213));
+#5907=CARTESIAN_POINT('Ctrl Pts',(-204.312705307154,-114.603964202848,1.81895624960821));
+#5908=CARTESIAN_POINT('Ctrl Pts',(-204.422359277988,-114.358028442314,1.87906267989088));
+#5909=CARTESIAN_POINT('Ctrl Pts',(-204.582982544804,-114.130615040248,1.9189800522226));
+#5910=CARTESIAN_POINT('Ctrl Pts',(-204.683519054854,-114.012105593863,1.92989073448492));
+#5911=CARTESIAN_POINT('Ctrl Pts',(-204.738936990757,-113.953239080317,1.9354411392178));
+#5912=CARTESIAN_POINT('Ctrl Pts',(-204.787647753138,-113.90396099629,1.93949953517666));
+#5913=CARTESIAN_POINT('Ctrl Pts',(-204.87630305916,-113.821026339949,1.94574870072859));
+#5914=CARTESIAN_POINT('Ctrl Pts',(-205.038900543477,-113.690969291746,1.95370746136295));
+#5915=CARTESIAN_POINT('Ctrl Pts',(-205.276448208836,-113.546939769148,1.96071459199766));
+#5916=CARTESIAN_POINT('Ctrl Pts',(-205.533537864338,-113.441420956094,1.96528439254103));
+#5917=CARTESIAN_POINT('Ctrl Pts',(-205.768129873933,-113.379113133395,1.96825859287479));
+#5918=CARTESIAN_POINT('Ctrl Pts',(-205.939422367889,-113.352205216747,1.96993215957611));
+#5919=CARTESIAN_POINT('Ctrl Pts',(-206.077567280521,-113.341425546388,1.97107616333618));
+#5920=CARTESIAN_POINT('Ctrl Pts',(-206.146820229364,-113.339626336974,1.97158973323535));
+#5921=CARTESIAN_POINT('Ctrl Pts',(-206.181446600706,-113.339626336974,1.9718335406713));
+#5922=CARTESIAN_POINT('Ctrl Pts',(-204.181545770614,-111.875410224956,-0.028166459328702));
+#5923=CARTESIAN_POINT('Ctrl Pts',(-204.181545770614,-111.934362935494,-0.0281664593287018));
+#5924=CARTESIAN_POINT('Ctrl Pts',(-204.170085177843,-112.000157136579,-0.0261175114762334));
+#5925=CARTESIAN_POINT('Ctrl Pts',(-204.111625784414,-112.176207814647,-0.0172531302913596));
+#5926=CARTESIAN_POINT('Ctrl Pts',(-204.05267203177,-112.280858921903,-0.00940858040748096));
+#5927=CARTESIAN_POINT('Ctrl Pts',(-203.960697192134,-112.399717389127,-0.00309257274584562));
+#5928=CARTESIAN_POINT('Ctrl Pts',(-203.935396358488,-112.429095112523,-0.00177271764181056));
+#5929=CARTESIAN_POINT('Ctrl Pts',(-203.897750135727,-112.467627958821,-0.000612154055789245));
+#5930=CARTESIAN_POINT('Ctrl Pts',(-203.886466668584,-112.478590468198,-0.000354592545529174));
+#5931=CARTESIAN_POINT('Ctrl Pts',(-203.865839229462,-112.497462031921,-6.74938302880351E-5));
+#5932=CARTESIAN_POINT('Ctrl Pts',(-203.856548424746,-112.505568493773,3.01662004896714E-15));
+#5933=CARTESIAN_POINT('Ctrl Pts',(-203.847072321916,-112.513393250479,3.05311331771918E-15));
+#5934=CARTESIAN_POINT('Origin',(-217.181545770614,-111.339626336974,2.4718335406713));
+#5935=CARTESIAN_POINT('',(-217.181545770614,-113.339626336974,9.9718335406713));
+#5936=CARTESIAN_POINT('',(-219.181545770614,-111.339626336974,9.9718335406713));
+#5937=CARTESIAN_POINT('Origin',(-217.181545770614,-111.339626336974,9.9718335406713));
+#5938=CARTESIAN_POINT('',(-219.181545770614,-111.339626336974,2.4718335406713));
+#5939=CARTESIAN_POINT('',(-217.181545770614,-113.339626336974,2.4718335406713));
+#5940=CARTESIAN_POINT('Origin',(-217.181545770614,-83.3396263369739,1.97183354067129));
+#5941=CARTESIAN_POINT('',(-217.181545770614,-81.3396263369739,1.97183354067129));
+#5942=CARTESIAN_POINT('',(-219.181545770614,-83.3396263369739,1.97183354067129));
+#5943=CARTESIAN_POINT('Origin',(-217.181545770614,-83.3396263369739,1.97183354067129));
+#5944=CARTESIAN_POINT('Origin',(-217.181545770614,-83.3396263369739,1.97183354067129));
+#5945=CARTESIAN_POINT('Origin',(-217.181545770614,-83.3396263369739,1.97183354067129));
+#5946=CARTESIAN_POINT('Origin',(-204.181545770614,-83.3396263369739,1.97183354067129));
+#5947=CARTESIAN_POINT('',(-206.018379808514,-81.3396263369739,1.97183353751381));
+#5948=CARTESIAN_POINT('',(-204.181545770614,-81.3396263369739,1.97183354067129));
+#5949=CARTESIAN_POINT('Origin',(-206.018379808514,-83.3396263369739,1.97183354067129));
+#5950=CARTESIAN_POINT('Ctrl Pts',(-206.018379808525,-81.3396263369739,1.97183354067105));
+#5951=CARTESIAN_POINT('Ctrl Pts',(-205.983744930132,-81.3396263369733,1.97158631444701));
+#5952=CARTESIAN_POINT('Ctrl Pts',(-205.914496663952,-81.3378163032199,1.97112602925702));
+#5953=CARTESIAN_POINT('Ctrl Pts',(-205.776310269244,-81.3270453353542,1.9698100574251));
+#5954=CARTESIAN_POINT('Ctrl Pts',(-205.536590182619,-81.2892818555558,1.96804928560445));
+#5955=CARTESIAN_POINT('Ctrl Pts',(-205.072181745294,-81.1401094468267,1.95915898290361));
+#5956=CARTESIAN_POINT('Ctrl Pts',(-204.670447513158,-80.8509320140667,1.95057736799509));
+#5957=CARTESIAN_POINT('Ctrl Pts',(-204.360767899834,-80.4755387273021,1.90407680035556));
+#5958=CARTESIAN_POINT('Ctrl Pts',(-204.217867357957,-80.2355874559968,1.85858222156802));
+#5959=CARTESIAN_POINT('Ctrl Pts',(-204.114454910626,-80.0099265836101,1.70552641464493));
+#5960=CARTESIAN_POINT('Ctrl Pts',(-204.03417523716,-79.8942690046825,1.48031920670113));
+#5961=CARTESIAN_POINT('Ctrl Pts',(-203.93149718148,-79.827582730216,1.23007254481972));
+#5962=CARTESIAN_POINT('Ctrl Pts',(-203.784356801117,-79.7773567083351,0.952515520892855));
+#5963=CARTESIAN_POINT('Ctrl Pts',(-203.520339627718,-79.727121787893,0.613439347833636));
+#5964=CARTESIAN_POINT('Ctrl Pts',(-203.153386804157,-79.6767679537557,0.317221552625942));
+#5965=CARTESIAN_POINT('Ctrl Pts',(-202.814040968277,-79.6361322440304,0.146952687950698));
+#5966=CARTESIAN_POINT('Ctrl Pts',(-202.492977414214,-79.6040104369857,0.0473734156740039));
+#5967=CARTESIAN_POINT('Ctrl Pts',(-202.312734091326,-79.5897011124912,0.0130149773866172));
+#5968=CARTESIAN_POINT('Ctrl Pts',(-202.194066967875,-79.5836077949982,-4.24660306919122E-14));
+#5969=CARTESIAN_POINT('Ctrl Pts',(-206.018379808525,-81.339626336974,1.37343493998733));
+#5970=CARTESIAN_POINT('Ctrl Pts',(-205.983857548707,-81.3397026074336,1.37323504975003));
+#5971=CARTESIAN_POINT('Ctrl Pts',(-205.914761306509,-81.3379412619123,1.37282570793299));
+#5972=CARTESIAN_POINT('Ctrl Pts',(-205.776814929366,-81.3274017371592,1.37171301044754));
+#5973=CARTESIAN_POINT('Ctrl Pts',(-205.537683069014,-81.2901953616376,1.37019852856921));
+#5974=CARTESIAN_POINT('Ctrl Pts',(-205.072261096265,-81.1418682517468,1.36255025038298));
+#5975=CARTESIAN_POINT('Ctrl Pts',(-204.669740315028,-80.8547270136582,1.35495683899147));
+#5976=CARTESIAN_POINT('Ctrl Pts',(-204.348177248692,-80.4854292466974,1.31728771361541));
+#5977=CARTESIAN_POINT('Ctrl Pts',(-204.192892354866,-80.2506546726453,1.28060834759468));
+#5978=CARTESIAN_POINT('Ctrl Pts',(-204.04870701333,-80.0351674776375,1.16009307321994));
+#5979=CARTESIAN_POINT('Ctrl Pts',(-203.916367868742,-79.9300521191363,0.989239981722529));
+#5980=CARTESIAN_POINT('Ctrl Pts',(-203.768746800687,-79.8721014767341,0.806581361958665));
+#5981=CARTESIAN_POINT('Ctrl Pts',(-203.58615876659,-79.8292131968854,0.610573577075453));
+#5982=CARTESIAN_POINT('Ctrl Pts',(-203.307951459716,-79.7840696427306,0.381252387564376));
+#5983=CARTESIAN_POINT('Ctrl Pts',(-202.966644775427,-79.7335883545206,0.188806199788165));
+#5984=CARTESIAN_POINT('Ctrl Pts',(-202.671852111491,-79.6893506466906,0.0810701170830327));
+#5985=CARTESIAN_POINT('Ctrl Pts',(-202.400402718732,-79.6531329256755,0.0187313942898858));
+#5986=CARTESIAN_POINT('Ctrl Pts',(-202.249818338169,-79.6366818717248,-0.00262539328074349));
+#5987=CARTESIAN_POINT('Ctrl Pts',(-202.150898537017,-79.6296422768512,-0.0107048228220918));
+#5988=CARTESIAN_POINT('Ctrl Pts',(-206.018379808517,-81.8418324948799,0.337507084904109));
+#5989=CARTESIAN_POINT('Ctrl Pts',(-205.975020859975,-81.8419501455678,0.337446884513242));
+#5990=CARTESIAN_POINT('Ctrl Pts',(-205.888353146832,-81.8399550529967,0.337345597056391));
+#5991=CARTESIAN_POINT('Ctrl Pts',(-205.715235691125,-81.8270719225719,0.337043591577801));
+#5992=CARTESIAN_POINT('Ctrl Pts',(-205.415082367591,-81.7809079096717,0.336633457320406));
+#5993=CARTESIAN_POINT('Ctrl Pts',(-204.831400941953,-81.5976002432724,0.334658968153168));
+#5994=CARTESIAN_POINT('Ctrl Pts',(-204.325411790323,-81.2402205713699,0.33271268141224));
+#5995=CARTESIAN_POINT('Ctrl Pts',(-203.918394204186,-80.7795774799116,0.32174789301672));
+#5996=CARTESIAN_POINT('Ctrl Pts',(-203.720059725921,-80.4868753084845,0.310988658363262));
+#5997=CARTESIAN_POINT('Ctrl Pts',(-203.534623972644,-80.2197095384028,0.276017480383811));
+#5998=CARTESIAN_POINT('Ctrl Pts',(-203.379341507937,-80.0899183122824,0.22785351958318));
+#5999=CARTESIAN_POINT('Ctrl Pts',(-203.229257005721,-80.0184099217367,0.178248930199111));
+#6000=CARTESIAN_POINT('Ctrl Pts',(-203.064476985739,-79.9651964884037,0.126766388902648));
+#6001=CARTESIAN_POINT('Ctrl Pts',(-202.845569735573,-79.908312670722,0.0690931329067971));
+#6002=CARTESIAN_POINT('Ctrl Pts',(-202.605630106273,-79.843913761239,0.0225825667380977));
+#6003=CARTESIAN_POINT('Ctrl Pts',(-202.410940988935,-79.7873113579928,-0.00278626489808406));
+#6004=CARTESIAN_POINT('Ctrl Pts',(-202.235331457734,-79.7409351336856,-0.0173200098800968));
+#6005=CARTESIAN_POINT('Ctrl Pts',(-202.138530227147,-79.7198755417593,-0.0222623695413706));
+#6006=CARTESIAN_POINT('Ctrl Pts',(-202.074738195022,-79.7108590783841,-0.0241318821075767));
+#6007=CARTESIAN_POINT('Ctrl Pts',(-206.018379808499,-82.8908273864611,-0.0281664593287026));
+#6008=CARTESIAN_POINT('Ctrl Pts',(-205.956865503349,-82.8908623268504,-0.0281658330503909));
+#6009=CARTESIAN_POINT('Ctrl Pts',(-205.833870857371,-82.8877390122849,-0.0281862811010682));
+#6010=CARTESIAN_POINT('Ctrl Pts',(-205.588416219942,-82.8688028556711,-0.0282141832541481));
+#6011=CARTESIAN_POINT('Ctrl Pts',(-205.162568528472,-82.8020833304095,-0.0282571074998647));
+#6012=CARTESIAN_POINT('Ctrl Pts',(-204.337264994443,-82.538309595338,-0.0285397417099887));
+#6013=CARTESIAN_POINT('Ctrl Pts',(-203.622341746984,-82.0262247053668,-0.028860538034685));
+#6014=CARTESIAN_POINT('Ctrl Pts',(-203.06863992123,-81.3623356384514,-0.029003014024956));
+#6015=CARTESIAN_POINT('Ctrl Pts',(-202.811098381075,-80.9384840818458,-0.0290532376845426));
+#6016=CARTESIAN_POINT('Ctrl Pts',(-202.630162018845,-80.5423000108261,-0.0289682491914576));
+#6017=CARTESIAN_POINT('Ctrl Pts',(-202.532823147664,-80.341349243795,-0.0286888026935958));
+#6018=CARTESIAN_POINT('Ctrl Pts',(-202.461774602642,-80.2264740960607,-0.0284525906994509));
+#6019=CARTESIAN_POINT('Ctrl Pts',(-202.393812488229,-80.1401507364947,-0.0282790244520186));
+#6020=CARTESIAN_POINT('Ctrl Pts',(-202.309846452921,-80.052730983868,-0.0281798431706056));
+#6021=CARTESIAN_POINT('Ctrl Pts',(-202.21788902671,-79.9629080935945,-0.0281544849300558));
+#6022=CARTESIAN_POINT('Ctrl Pts',(-202.140726792661,-79.889038696687,-0.0281606728661386));
+#6023=CARTESIAN_POINT('Ctrl Pts',(-202.06791828804,-79.830155945788,-0.02816346947471));
+#6024=CARTESIAN_POINT('Ctrl Pts',(-202.026348897133,-79.8038058121625,-0.0281665241826855));
+#6025=CARTESIAN_POINT('Ctrl Pts',(-201.998114298949,-79.792570210413,-0.0281664593287107));
+#6026=CARTESIAN_POINT('Ctrl Pts',(-206.018379808491,-83.3396263369739,-0.0281664593287026));
+#6027=CARTESIAN_POINT('Ctrl Pts',(-205.949113581501,-83.3396263369727,-0.0281664593287031));
+#6028=CARTESIAN_POINT('Ctrl Pts',(-205.810597028159,-83.3360062694659,-0.0281664593287087));
+#6029=CARTESIAN_POINT('Ctrl Pts',(-205.534240192166,-83.3144643337345,-0.0281664593286971));
+#6030=CARTESIAN_POINT('Ctrl Pts',(-205.054701905816,-83.2389373741377,-0.0281664593286989));
+#6031=CARTESIAN_POINT('Ctrl Pts',(-204.126103070476,-82.9405925566796,-0.0281664593287078));
+#6032=CARTESIAN_POINT('Ctrl Pts',(-203.321929796765,-82.3622376911595,-0.0281664593287095));
+#6033=CARTESIAN_POINT('Ctrl Pts',(-202.705558645264,-81.6114511176303,-0.0281664593287108));
+#6034=CARTESIAN_POINT('Ctrl Pts',(-202.422713023496,-81.1315485750197,-0.0281664593287102));
+#6035=CARTESIAN_POINT('Ctrl Pts',(-202.243575166383,-80.6802268302465,-0.0281664593287105));
+#6036=CARTESIAN_POINT('Ctrl Pts',(-202.170773504378,-80.4489116723912,-0.0281664593287101));
+#6037=CARTESIAN_POINT('Ctrl Pts',(-202.133317637968,-80.3155391234583,-0.0281664593287103));
+#6038=CARTESIAN_POINT('Ctrl Pts',(-202.106612024325,-80.2150870796965,-0.0281664593287105));
+#6039=CARTESIAN_POINT('Ctrl Pts',(-202.080311373824,-80.1146172388122,-0.0281664593287113));
+#6040=CARTESIAN_POINT('Ctrl Pts',(-202.051718230959,-80.0139095705376,-0.0281664593287101));
+#6041=CARTESIAN_POINT('Ctrl Pts',(-202.024919865031,-79.9326381510869,-0.028166459328712));
+#6042=CARTESIAN_POINT('Ctrl Pts',(-201.996168571406,-79.8683945369976,-0.0281664593287104));
+#6043=CARTESIAN_POINT('Ctrl Pts',(-201.978271233044,-79.8397758880085,-0.0281664593287108));
+#6044=CARTESIAN_POINT('Ctrl Pts',(-201.96527549945,-79.8275892530225,-0.0281664593287106));
+#6045=CARTESIAN_POINT('',(-203.847072321916,-82.2929574942446,0.));
+#6046=CARTESIAN_POINT('Ctrl Pts',(-203.847185069941,-82.2927139227897,0.000333642019854752));
+#6047=CARTESIAN_POINT('Ctrl Pts',(-203.862379752472,-82.3038813318013,0.000336473739380365));
+#6048=CARTESIAN_POINT('Ctrl Pts',(-203.877148524617,-82.3158236758352,0.000163196135680087));
+#6049=CARTESIAN_POINT('Ctrl Pts',(-203.891354816203,-82.3282265879518,-0.000151847287857054));
+#6050=CARTESIAN_POINT('Ctrl Pts',(-203.910655425345,-82.3450771331865,-0.000579863983397397));
+#6051=CARTESIAN_POINT('Ctrl Pts',(-203.92924858369,-82.3630665339288,-0.00127708591012739));
+#6052=CARTESIAN_POINT('Ctrl Pts',(-203.946940066271,-82.3817293791502,-0.00216881431410398));
+#6053=CARTESIAN_POINT('Ctrl Pts',(-203.951058373632,-82.3860738049206,-0.00237639508822984));
+#6054=CARTESIAN_POINT('Ctrl Pts',(-203.955127609868,-82.3904547765801,-0.00259446524107934));
+#6055=CARTESIAN_POINT('Ctrl Pts',(-203.95914493383,-82.3948665089525,-0.0028220087864978));
+#6056=CARTESIAN_POINT('Ctrl Pts',(-203.979022706895,-82.416695820146,-0.0039478973136577));
+#6057=CARTESIAN_POINT('Ctrl Pts',(-203.998031477712,-82.4397217207066,-0.00533066227045333));
+#6058=CARTESIAN_POINT('Ctrl Pts',(-204.015983988594,-82.4636232114241,-0.00687147871750954));
+#6059=CARTESIAN_POINT('Ctrl Pts',(-204.033766239789,-82.4872980229674,-0.00839768222665576));
+#6060=CARTESIAN_POINT('Ctrl Pts',(-204.050512407383,-82.511832363054,-0.010078330628785));
+#6061=CARTESIAN_POINT('Ctrl Pts',(-204.065991131081,-82.5369192197065,-0.0118055336562677));
+#6062=CARTESIAN_POINT('Ctrl Pts',(-204.07125404705,-82.5454489939361,-0.0123927994136773));
+#6063=CARTESIAN_POINT('Ctrl Pts',(-204.076369999814,-82.5540426535975,-0.0129853866117259));
+#6064=CARTESIAN_POINT('Ctrl Pts',(-204.081328520699,-82.5626881131704,-0.0135789256831079));
+#6065=CARTESIAN_POINT('Ctrl Pts',(-204.095780087498,-82.5878852313038,-0.0153087902405882));
+#6066=CARTESIAN_POINT('Ctrl Pts',(-204.109162362138,-82.6139783410812,-0.0170787887606727));
+#6067=CARTESIAN_POINT('Ctrl Pts',(-204.121159792099,-82.6407016995622,-0.0187664201304509));
+#6068=CARTESIAN_POINT('Ctrl Pts',(-204.132951695554,-82.6669672634591,-0.0204251408937418));
+#6069=CARTESIAN_POINT('Ctrl Pts',(-204.143405863446,-82.6938422729444,-0.0220039594157461));
+#6070=CARTESIAN_POINT('Ctrl Pts',(-204.152173068176,-82.7210696960385,-0.0233789371864456));
+#6071=CARTESIAN_POINT('Ctrl Pts',(-204.15448603312,-82.7282528378821,-0.0237416839776001));
+#6072=CARTESIAN_POINT('Ctrl Pts',(-204.156681309916,-82.7354604540905,-0.0240902161870443));
+#6073=CARTESIAN_POINT('Ctrl Pts',(-204.158751893873,-82.7426876821551,-0.0244222107757314));
+#6074=CARTESIAN_POINT('Ctrl Pts',(-204.165718599708,-82.7670044802055,-0.0255392428238067));
+#6075=CARTESIAN_POINT('Ctrl Pts',(-204.171391997486,-82.7919602277578,-0.0264876320457484));
+#6076=CARTESIAN_POINT('Ctrl Pts',(-204.175340872569,-82.8171402582199,-0.0271492066608737));
+#6077=CARTESIAN_POINT('Ctrl Pts',(-204.179088476137,-82.8410368794202,-0.0277770612616543));
+#6078=CARTESIAN_POINT('Ctrl Pts',(-204.181282351092,-82.8651360506659,-0.0281462954643738));
+#6079=CARTESIAN_POINT('Ctrl Pts',(-204.181506027807,-82.8890665601067,-0.0281662670731122));
+#6080=CARTESIAN_POINT('Ctrl Pts',(-204.181518040751,-82.8903517893949,-0.0281673396828093));
+#6081=CARTESIAN_POINT('Ctrl Pts',(-204.181524359973,-82.8916365267729,-0.0281674080701182));
+#6082=CARTESIAN_POINT('Ctrl Pts',(-204.1815249173,-82.8929207127805,-0.0281664593287061));
+#6083=CARTESIAN_POINT('',(-202.194066967875,-79.5836077949982,-3.19189119579733E-15));
+#6084=CARTESIAN_POINT('Ctrl Pts',(-206.018379808525,-81.3396263369739,1.97183354067105));
+#6085=CARTESIAN_POINT('Ctrl Pts',(-205.983744930132,-81.3396263369733,1.97158631444701));
+#6086=CARTESIAN_POINT('Ctrl Pts',(-205.914496663952,-81.3378163032199,1.97112602925702));
+#6087=CARTESIAN_POINT('Ctrl Pts',(-205.776310269244,-81.3270453353542,1.9698100574251));
+#6088=CARTESIAN_POINT('Ctrl Pts',(-205.536590182619,-81.2892818555558,1.96804928560445));
+#6089=CARTESIAN_POINT('Ctrl Pts',(-205.072181745294,-81.1401094468267,1.95915898290361));
+#6090=CARTESIAN_POINT('Ctrl Pts',(-204.670447513158,-80.8509320140667,1.95057736799509));
+#6091=CARTESIAN_POINT('Ctrl Pts',(-204.360767899834,-80.4755387273021,1.90407680035556));
+#6092=CARTESIAN_POINT('Ctrl Pts',(-204.217867357957,-80.2355874559968,1.85858222156802));
+#6093=CARTESIAN_POINT('Ctrl Pts',(-204.114454910626,-80.0099265836101,1.70552641464493));
+#6094=CARTESIAN_POINT('Ctrl Pts',(-204.03417523716,-79.8942690046825,1.48031920670113));
+#6095=CARTESIAN_POINT('Ctrl Pts',(-203.93149718148,-79.827582730216,1.23007254481972));
+#6096=CARTESIAN_POINT('Ctrl Pts',(-203.784356801117,-79.7773567083351,0.952515520892855));
+#6097=CARTESIAN_POINT('Ctrl Pts',(-203.520339627718,-79.727121787893,0.613439347833636));
+#6098=CARTESIAN_POINT('Ctrl Pts',(-203.153386804157,-79.6767679537557,0.317221552625942));
+#6099=CARTESIAN_POINT('Ctrl Pts',(-202.814040968277,-79.6361322440304,0.146952687950698));
+#6100=CARTESIAN_POINT('Ctrl Pts',(-202.492977414214,-79.6040104369857,0.0473734156740039));
+#6101=CARTESIAN_POINT('Ctrl Pts',(-202.312734091326,-79.5897011124912,0.0130149773866172));
+#6102=CARTESIAN_POINT('Ctrl Pts',(-202.194066967875,-79.5836077949982,-4.24660306919122E-14));
+#6103=CARTESIAN_POINT('Ctrl Pts',(-202.194066967875,-79.5836077949982,3.33066907387547E-15));
+#6104=CARTESIAN_POINT('Ctrl Pts',(-202.194566411931,-79.5840761442728,3.33066907387547E-15));
+#6105=CARTESIAN_POINT('Ctrl Pts',(-202.195064698078,-79.5845457239416,7.60502771868232E-14));
+#6106=CARTESIAN_POINT('Ctrl Pts',(-202.23834921369,-79.625538181728,7.60502771868232E-14));
+#6107=CARTESIAN_POINT('Ctrl Pts',(-202.26918234893,-79.6719238062248,5.27355936696949E-15));
+#6108=CARTESIAN_POINT('Ctrl Pts',(-202.355552318804,-79.8362467351125,5.27355936696949E-15));
+#6109=CARTESIAN_POINT('Ctrl Pts',(-202.394715400629,-79.9978115703195,1.94289029309402E-15));
+#6110=CARTESIAN_POINT('Ctrl Pts',(-202.45529084016,-80.2252028140545,1.94289029309402E-15));
+#6111=CARTESIAN_POINT('Ctrl Pts',(-202.468271908297,-80.2725511052259,1.49884286609446E-14));
+#6112=CARTESIAN_POINT('Ctrl Pts',(-202.499739163916,-80.3801342601221,1.49875471232931E-14));
+#6113=CARTESIAN_POINT('Ctrl Pts',(-202.516987660241,-80.4352610305252,1.24898374758296E-14));
+#6114=CARTESIAN_POINT('Ctrl Pts',(-202.587050898501,-80.6429463272335,1.24904786793623E-14));
+#6115=CARTESIAN_POINT('Ctrl Pts',(-202.646560457275,-80.7891640018208,-2.27595720048157E-14));
+#6116=CARTESIAN_POINT('Ctrl Pts',(-202.85243473036,-81.2142243697153,-2.27595720048157E-14));
+#6117=CARTESIAN_POINT('Ctrl Pts',(-203.023420013188,-81.4765799736513,4.44089209850063E-15));
+#6118=CARTESIAN_POINT('Ctrl Pts',(-203.410350420912,-81.9312429676097,4.44089209850063E-15));
+#6119=CARTESIAN_POINT('Ctrl Pts',(-203.618885458724,-82.1252339879281,-6.11813230558808E-15));
+#6120=CARTESIAN_POINT('Ctrl Pts',(-203.847072321916,-82.2929574942445,-6.11813105724368E-15));
+#6121=CARTESIAN_POINT('Origin',(-217.181545770614,-89.3396263369739,1.97183354067129));
+#6122=CARTESIAN_POINT('',(-219.181545770614,-89.3396263369739,1.97183354067129));
+#6123=CARTESIAN_POINT('Origin',(-217.181545770614,-83.3396263369739,7.47183354067129));
+#6124=CARTESIAN_POINT('',(-219.181545770614,-83.3396263369739,9.97183354067129));
+#6125=CARTESIAN_POINT('',(-217.181545770614,-81.3396263369739,9.97183354067129));
+#6126=CARTESIAN_POINT('Origin',(-217.181545770614,-83.3396263369739,9.9718335406713));
+#6127=CARTESIAN_POINT('',(-217.181545770614,-81.3396263369739,7.47183354067129));
+#6128=CARTESIAN_POINT('',(-219.181545770614,-83.3396263369739,7.47183354067129));
+#6129=CARTESIAN_POINT('Origin',(-204.181545770614,-113.339626336974,-0.0281664593287018));
+#6130=CARTESIAN_POINT('',(-206.181545770614,-113.339626336974,2.));
+#6131=CARTESIAN_POINT('Origin',(-202.181545770614,-113.339626336974,2.));
+#6132=CARTESIAN_POINT('',(-206.181545770614,-113.339626336974,9.9718335406713));
+#6133=CARTESIAN_POINT('',(-206.181545770614,-113.339626336974,-0.0140832296643473));
+#6134=CARTESIAN_POINT('',(-204.181545770614,-113.339626336974,9.9718335406713));
+#6135=CARTESIAN_POINT('Origin',(-202.181545770614,-115.339626336974,2.));
+#6136=CARTESIAN_POINT('',(-202.181545770614,-115.339626336974,0.));
+#6137=CARTESIAN_POINT('Ctrl Pts',(-202.420153328716,-115.101863333037,-2.15446712763374E-19));
+#6138=CARTESIAN_POINT('Ctrl Pts',(-202.338597753443,-115.182555954865,-2.57852953110006E-19));
+#6139=CARTESIAN_POINT('Ctrl Pts',(-202.258986139879,-115.262185967709,-3.43904323973088E-17));
+#6140=CARTESIAN_POINT('Ctrl Pts',(-202.181545770614,-115.339626336974,0.));
+#6141=CARTESIAN_POINT('',(-204.181545770614,-115.339626336974,2.));
+#6142=CARTESIAN_POINT('Origin',(-202.181545770614,-115.339626336974,2.));
+#6143=CARTESIAN_POINT('Origin',(-206.181545770614,-115.339626336974,2.));
+#6144=CARTESIAN_POINT('Origin',(-134.181545770614,-106.311168852415,0.));
+#6145=CARTESIAN_POINT('',(-203.847072321916,-81.3396263369739,0.));
+#6146=CARTESIAN_POINT('',(-201.934804447442,-79.3396263369738,0.));
+#6147=CARTESIAN_POINT('Ctrl Pts',(-201.934804447442,-79.3396263369739,1.66533453693773E-15));
+#6148=CARTESIAN_POINT('Ctrl Pts',(-201.93752675805,-79.34218803955,1.6849003402075E-15));
+#6149=CARTESIAN_POINT('Ctrl Pts',(-201.940248903624,-79.3447498781388,2.77557173164117E-16));
+#6150=CARTESIAN_POINT('Ctrl Pts',(-202.026130951108,-79.4255826840024,2.77512465577715E-16));
+#6151=CARTESIAN_POINT('Ctrl Pts',(-202.109765735281,-79.5045550548781,-7.49400541621981E-15));
+#6152=CARTESIAN_POINT('Ctrl Pts',(-202.194066967875,-79.5836077949982,-7.49400541621981E-15));
+#6153=CARTESIAN_POINT('',(-191.58695117602,-73.7436012848473,0.));
+#6154=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,0.));
+#6155=CARTESIAN_POINT('',(-76.7761403652087,-73.7436012848473,0.));
+#6156=CARTESIAN_POINT('Origin',(-134.181545770614,93.6888311475868,0.));
+#6157=CARTESIAN_POINT('',(-66.1815457706142,-81.3111688524149,0.));
+#6158=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,0.));
+#6159=CARTESIAN_POINT('',(-66.1815457706141,-120.015430341809,0.));
+#6160=CARTESIAN_POINT('',(-66.1815457706141,-113.163299597112,0.));
+#6161=CARTESIAN_POINT('',(-71.2724548615232,-127.467758171598,0.));
+#6162=CARTESIAN_POINT('Origin',(-74.1815457706141,-120.015430341809,0.));
+#6163=CARTESIAN_POINT('',(-105.836913002253,-136.973355036779,0.));
+#6164=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,0.));
+#6165=CARTESIAN_POINT('',(-109.181545770614,-140.919301538152,0.));
+#6166=CARTESIAN_POINT('Origin',(-105.181545770614,-140.919301538152,0.));
+#6167=CARTESIAN_POINT('',(-109.181545770614,-142.311168852415,0.));
+#6168=CARTESIAN_POINT('',(-109.181545770614,-125.311168852415,0.));
+#6169=CARTESIAN_POINT('',(-159.181545770614,-142.311168852415,0.));
+#6170=CARTESIAN_POINT('',(-147.681545770614,-142.311168852415,0.));
+#6171=CARTESIAN_POINT('',(-159.181545770614,-140.919301538152,0.));
+#6172=CARTESIAN_POINT('',(-159.181545770614,-122.763467838619,0.));
+#6173=CARTESIAN_POINT('',(-162.526178538976,-136.973355036779,0.));
+#6174=CARTESIAN_POINT('Origin',(-163.181545770614,-140.919301538152,0.));
+#6175=CARTESIAN_POINT('',(-197.090636679705,-127.467758171598,0.));
+#6176=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,0.));
+#6177=CARTESIAN_POINT('',(-202.181545770614,-120.015430341809,0.));
+#6178=CARTESIAN_POINT('Origin',(-194.181545770614,-120.015430341809,0.));
+#6179=CARTESIAN_POINT('',(-202.181545770614,-93.8111688524148,0.));
+#6180=CARTESIAN_POINT('',(-139.681545770614,-126.482328591575,0.));
+#6181=CARTESIAN_POINT('',(-139.681545770614,-133.482328591575,0.));
+#6182=CARTESIAN_POINT('',(-139.681545770614,-119.896748721995,0.));
+#6183=CARTESIAN_POINT('',(-128.681545770614,-133.482328591575,0.));
+#6184=CARTESIAN_POINT('',(-131.431545770614,-133.482328591575,0.));
+#6185=CARTESIAN_POINT('',(-128.681545770614,-126.482328591575,0.));
+#6186=CARTESIAN_POINT('',(-128.681545770614,-116.396748721995,0.));
+#6187=CARTESIAN_POINT('',(-136.931545770614,-126.482328591575,0.));
+#6188=CARTESIAN_POINT('',(-153.681545770614,-124.687409348463,0.));
+#6189=CARTESIAN_POINT('',(-164.681545770614,-124.687409348463,0.));
+#6190=CARTESIAN_POINT('',(-149.431545770614,-124.687409348463,0.));
+#6191=CARTESIAN_POINT('',(-164.681545770614,-131.687409348463,0.));
+#6192=CARTESIAN_POINT('',(-164.681545770614,-118.999289100439,0.));
+#6193=CARTESIAN_POINT('',(-153.681545770614,-131.687409348463,0.));
+#6194=CARTESIAN_POINT('',(-143.931545770614,-131.687409348463,0.));
+#6195=CARTESIAN_POINT('',(-153.681545770614,-115.499289100439,0.));
+#6196=CARTESIAN_POINT('',(-103.681545770614,-131.687409348463,0.));
+#6197=CARTESIAN_POINT('',(-103.681545770614,-124.687409348463,0.));
+#6198=CARTESIAN_POINT('',(-103.681545770614,-115.499289100439,0.));
+#6199=CARTESIAN_POINT('',(-114.681545770614,-124.687409348463,0.));
+#6200=CARTESIAN_POINT('',(-124.431545770614,-124.687409348463,0.));
+#6201=CARTESIAN_POINT('',(-114.681545770614,-131.687409348463,0.));
+#6202=CARTESIAN_POINT('',(-114.681545770614,-118.999289100439,0.));
+#6203=CARTESIAN_POINT('',(-118.931545770614,-131.687409348463,0.));
+#6204=CARTESIAN_POINT('',(-178.681545770614,-126.18742690406,0.));
+#6205=CARTESIAN_POINT('',(-178.681545770614,-119.18742690406,0.));
+#6206=CARTESIAN_POINT('',(-178.681545770614,-112.749297878237,0.));
+#6207=CARTESIAN_POINT('',(-189.681545770614,-119.18742690406,0.));
+#6208=CARTESIAN_POINT('',(-161.931545770614,-119.18742690406,0.));
+#6209=CARTESIAN_POINT('',(-189.681545770614,-126.18742690406,0.));
+#6210=CARTESIAN_POINT('',(-189.681545770614,-116.249297878237,0.));
+#6211=CARTESIAN_POINT('',(-156.431545770614,-126.18742690406,0.));
+#6212=CARTESIAN_POINT('',(-89.6815457706142,-119.18742690406,0.));
+#6213=CARTESIAN_POINT('',(-89.6815457706142,-126.18742690406,0.));
+#6214=CARTESIAN_POINT('',(-89.6815457706142,-116.249297878237,0.));
+#6215=CARTESIAN_POINT('',(-78.6815457706143,-126.18742690406,0.));
+#6216=CARTESIAN_POINT('',(-106.431545770614,-126.18742690406,0.));
+#6217=CARTESIAN_POINT('',(-78.6815457706143,-119.18742690406,0.));
+#6218=CARTESIAN_POINT('',(-78.6815457706143,-112.749297878237,0.));
+#6219=CARTESIAN_POINT('',(-111.931545770614,-119.18742690406,0.));
+#6220=CARTESIAN_POINT('Origin',(-203.847072321916,-81.3396263369739,-2.));
+#6221=CARTESIAN_POINT('Origin',(-206.181545770614,-115.339626336974,-0.0140832296643469));
+#6222=CARTESIAN_POINT('',(-204.181545770614,-115.339626336974,9.9718335406713));
+#6223=CARTESIAN_POINT('',(-204.181545770614,-115.339626336974,-0.0140832296643469));
+#6224=CARTESIAN_POINT('Origin',(-206.181545770614,-115.339626336974,9.9718335406713));
+#6225=CARTESIAN_POINT('Origin',(-206.018480344642,-79.3396263369739,0.));
+#6226=CARTESIAN_POINT('',(-204.045657915637,-79.6682167562141,9.97183354067129));
+#6227=CARTESIAN_POINT('',(-206.018480344642,-81.3396263369739,9.97183354067129));
+#6228=CARTESIAN_POINT('Origin',(-206.018480344642,-79.3396263369739,9.9718335406713));
+#6229=CARTESIAN_POINT('',(-204.045657915637,-79.6682167562141,2.));
+#6230=CARTESIAN_POINT('',(-204.045657915637,-79.6682167562141,0.));
+#6231=CARTESIAN_POINT('',(-206.018480344642,-81.3396263369739,2.));
+#6232=CARTESIAN_POINT('Origin',(-206.018480344642,-79.3396263369739,2.));
+#6233=CARTESIAN_POINT('',(-206.018480344642,-81.3396263369739,0.));
+#6234=CARTESIAN_POINT('Ctrl Pts',(-206.018480344642,-81.3396263369739,2.));
+#6235=CARTESIAN_POINT('Ctrl Pts',(-206.018480344642,-81.3396263369739,1.398687162962));
+#6236=CARTESIAN_POINT('Ctrl Pts',(-205.73326658499,-81.3396263369739,0.187989081731175));
+#6237=CARTESIAN_POINT('Ctrl Pts',(-204.355283981247,-81.3396263369739,-1.49275123469899));
+#6238=CARTESIAN_POINT('Ctrl Pts',(-202.838436451967,-81.3396263369739,-2.00000000000001));
+#6239=CARTESIAN_POINT('Ctrl Pts',(-201.934804447442,-81.3396263369739,-2.));
+#6240=CARTESIAN_POINT('Ctrl Pts',(-205.482955446498,-81.3396263369739,2.));
+#6241=CARTESIAN_POINT('Ctrl Pts',(-205.482955446498,-81.3396263369739,1.48053453347068));
+#6242=CARTESIAN_POINT('Ctrl Pts',(-205.232832392488,-81.3388895567542,0.433808699003294));
+#6243=CARTESIAN_POINT('Ctrl Pts',(-204.029506256522,-81.3393028504634,-1.00778161619426));
+#6244=CARTESIAN_POINT('Ctrl Pts',(-202.710896866348,-81.338766284856,-1.4226141610988));
+#6245=CARTESIAN_POINT('Ctrl Pts',(-201.934804447442,-81.3396263369739,-1.40160139931623));
+#6246=CARTESIAN_POINT('Ctrl Pts',(-204.552268220504,-80.9422929672336,2.));
+#6247=CARTESIAN_POINT('Ctrl Pts',(-204.552268220504,-80.9422929672336,1.62205769742118));
+#6248=CARTESIAN_POINT('Ctrl Pts',(-204.364809399444,-80.9380517465748,0.861852415820645));
+#6249=CARTESIAN_POINT('Ctrl Pts',(-203.464638461074,-80.9128088625103,-0.167002581542881));
+#6250=CARTESIAN_POINT('Ctrl Pts',(-202.491840471636,-80.8742008471114,-0.420124519350226));
+#6251=CARTESIAN_POINT('Ctrl Pts',(-201.934804447442,-80.837420188731,-0.365673536183614));
+#6252=CARTESIAN_POINT('Ctrl Pts',(-204.111646047185,-80.0644025800947,2.));
+#6253=CARTESIAN_POINT('Ctrl Pts',(-204.111646047185,-80.0644025800947,1.68943452808622));
+#6254=CARTESIAN_POINT('Ctrl Pts',(-203.958653137862,-80.0523537576684,1.06377874336536));
+#6255=CARTESIAN_POINT('Ctrl Pts',(-203.221988826898,-79.9841163709952,0.208421507822904));
+#6256=CARTESIAN_POINT('Ctrl Pts',(-202.413735116368,-79.8811695036547,-0.0244286440504637));
+#6257=CARTESIAN_POINT('Ctrl Pts',(-201.934804447442,-79.7884252874867,3.97076036236738E-15));
+#6258=CARTESIAN_POINT('Ctrl Pts',(-204.045657915637,-79.6682167562141,2.));
+#6259=CARTESIAN_POINT('Ctrl Pts',(-204.045657915637,-79.6682167562141,1.69934358148054));
+#6260=CARTESIAN_POINT('Ctrl Pts',(-203.900716762161,-79.653274200596,1.09399454086554));
+#6261=CARTESIAN_POINT('Ctrl Pts',(-203.197146041502,-79.570939430303,0.253624382650044));
+#6262=CARTESIAN_POINT('Ctrl Pts',(-202.41406107025,-79.4475389118585,-3.8233697750191E-15));
+#6263=CARTESIAN_POINT('Ctrl Pts',(-201.934804447442,-79.3396263369739,1.94289029309402E-15));
+#6264=CARTESIAN_POINT('Ctrl Pts',(-206.018376176897,-81.3396263369738,1.97183989609268));
+#6265=CARTESIAN_POINT('Ctrl Pts',(-206.01844560044,-81.3396263369739,1.98122741189999));
+#6266=CARTESIAN_POINT('Ctrl Pts',(-206.018480344642,-81.3396263369739,1.99061419763269));
+#6267=CARTESIAN_POINT('Ctrl Pts',(-206.018480344642,-81.3396263369739,2.));
+#6268=CARTESIAN_POINT('Ctrl Pts',(-204.045657915637,-79.6682167562141,2.));
+#6269=CARTESIAN_POINT('Ctrl Pts',(-204.045657915637,-79.6682167562141,1.69934358148054));
+#6270=CARTESIAN_POINT('Ctrl Pts',(-203.900716762161,-79.653274200596,1.09399454086554));
+#6271=CARTESIAN_POINT('Ctrl Pts',(-203.197146041502,-79.570939430303,0.253624382650044));
+#6272=CARTESIAN_POINT('Ctrl Pts',(-202.41406107025,-79.4475389118585,-3.8233697750191E-15));
+#6273=CARTESIAN_POINT('Ctrl Pts',(-201.934804447442,-79.3396263369739,1.94289029309402E-15));
+#6274=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,2.));
+#6275=CARTESIAN_POINT('',(-190.938302527371,-71.8517093929555,2.));
+#6276=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,2.));
+#6277=CARTESIAN_POINT('Origin',(-191.58695117602,-73.7436012848473,2.));
+#6278=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,0.));
+#6279=CARTESIAN_POINT('',(-204.181545770614,-81.3111688524149,9.97183354067129));
+#6280=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,9.9718335406713));
+#6281=CARTESIAN_POINT('',(-204.181545770614,-81.3111688524149,0.));
+#6282=CARTESIAN_POINT('',(-201.549446967915,-74.5499535809703,3.));
+#6283=CARTESIAN_POINT('',(-201.549446967915,-74.5499535809703,3.));
+#6284=CARTESIAN_POINT('',(-199.993927707805,-73.1738341403474,3.));
+#6285=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,3.));
+#6286=CARTESIAN_POINT('',(-199.993927707805,-73.1738341403474,3.));
+#6287=CARTESIAN_POINT('',(-190.938302527371,-71.8517093929555,0.));
+#6288=CARTESIAN_POINT('Origin',(-163.181545770614,-140.919301538152,1.99999999999999));
+#6289=CARTESIAN_POINT('',(-162.853862154795,-138.946328287466,2.));
+#6290=CARTESIAN_POINT('',(-161.181545770614,-140.919301538152,2.));
+#6291=CARTESIAN_POINT('Origin',(-163.181545770614,-140.919301538152,1.99999999999999));
+#6292=CARTESIAN_POINT('Origin',(-162.526178538976,-136.973355036779,2.));
+#6293=CARTESIAN_POINT('Origin',(-159.181545770614,-140.919301538152,2.));
+#6294=CARTESIAN_POINT('Origin',(-202.181545770614,-93.8111688524148,2.));
+#6295=CARTESIAN_POINT('',(-204.181545770614,-120.015430341809,2.));
+#6296=CARTESIAN_POINT('Origin',(-202.181545770614,-120.015430341809,2.));
+#6297=CARTESIAN_POINT('',(-204.181545770614,-93.8111688524148,2.));
+#6298=CARTESIAN_POINT('Origin',(-194.181545770614,-120.015430341809,2.));
+#6299=CARTESIAN_POINT('',(-197.817909406978,-129.330840129045,2.));
+#6300=CARTESIAN_POINT('Origin',(-197.090636679705,-127.467758171598,2.));
+#6301=CARTESIAN_POINT('Origin',(-194.181545770614,-120.015430341809,2.));
+#6302=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,2.));
+#6303=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,2.));
+#6304=CARTESIAN_POINT('Origin',(-159.181545770614,-142.311168852415,2.));
+#6305=CARTESIAN_POINT('',(-161.181545770614,-142.311168852415,2.));
+#6306=CARTESIAN_POINT('Origin',(-159.181545770614,-142.311168852415,2.));
+#6307=CARTESIAN_POINT('Origin',(-159.181545770614,-142.311168852415,2.));
+#6308=CARTESIAN_POINT('Origin',(-159.181545770614,-142.311168852415,2.));
+#6309=CARTESIAN_POINT('Origin',(-159.181545770614,-122.763467838619,2.));
+#6310=CARTESIAN_POINT('',(-161.181545770614,-122.763467838619,2.));
+#6311=CARTESIAN_POINT('Origin',(-109.181545770614,-142.311168852415,2.));
+#6312=CARTESIAN_POINT('',(-107.181545770614,-142.311168852415,2.));
+#6313=CARTESIAN_POINT('Origin',(-109.181545770614,-142.311168852415,2.));
+#6314=CARTESIAN_POINT('Origin',(-109.181545770614,-142.311168852415,2.));
+#6315=CARTESIAN_POINT('Origin',(-109.181545770614,-142.311168852415,2.));
+#6316=CARTESIAN_POINT('Origin',(-147.681545770614,-142.311168852415,2.));
+#6317=CARTESIAN_POINT('Origin',(-105.181545770614,-140.919301538152,1.99999999999997));
+#6318=CARTESIAN_POINT('',(-107.181545770614,-140.919301538152,2.));
+#6319=CARTESIAN_POINT('',(-105.509229386433,-138.946328287466,2.));
+#6320=CARTESIAN_POINT('Origin',(-105.181545770614,-140.919301538152,1.99999999999997));
+#6321=CARTESIAN_POINT('Origin',(-109.181545770614,-140.919301538152,2.));
+#6322=CARTESIAN_POINT('Origin',(-105.836913002253,-136.973355036779,2.));
+#6323=CARTESIAN_POINT('Origin',(-109.181545770614,-125.311168852415,2.));
+#6324=CARTESIAN_POINT('',(-107.181545770614,-125.311168852415,2.));
+#6325=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,2.));
+#6326=CARTESIAN_POINT('',(-70.5451821342505,-129.330840129045,2.));
+#6327=CARTESIAN_POINT('Origin',(-71.2724548615232,-127.467758171598,2.));
+#6328=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,2.));
+#6329=CARTESIAN_POINT('Origin',(-74.1815457706141,-120.015430341809,2.));
+#6330=CARTESIAN_POINT('',(-64.1815457706141,-120.015430341809,2.));
+#6331=CARTESIAN_POINT('Origin',(-66.1815457706141,-120.015430341809,2.));
+#6332=CARTESIAN_POINT('Origin',(-74.1815457706141,-120.015430341809,2.));
+#6333=CARTESIAN_POINT('Origin',(-66.1815457706141,-113.163299597112,2.));
+#6334=CARTESIAN_POINT('',(-64.1815457706142,-81.3111688524149,2.));
+#6335=CARTESIAN_POINT('Origin',(-66.1815457706142,-81.3111688524149,2.));
+#6336=CARTESIAN_POINT('',(-64.1815457706141,-113.163299597112,2.));
+#6337=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,2.));
+#6338=CARTESIAN_POINT('',(-77.4247890138573,-71.8517093929555,2.));
+#6339=CARTESIAN_POINT('Origin',(-76.7761403652087,-73.7436012848473,2.));
+#6340=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,2.));
+#6341=CARTESIAN_POINT('Origin',(-134.181545770614,93.6888311475868,2.));
+#6342=CARTESIAN_POINT('Origin',(-134.181545770614,93.6888311475868,2.));
+#6343=CARTESIAN_POINT('Origin',(-105.181545770614,-140.919301538152,0.));
+#6344=CARTESIAN_POINT('',(-107.181545770614,-140.919301538152,0.));
+#6345=CARTESIAN_POINT('',(-105.509229386433,-138.946328287466,0.));
+#6346=CARTESIAN_POINT('Origin',(-109.181545770614,-142.311168852415,0.));
+#6347=CARTESIAN_POINT('',(-107.181545770614,-142.311168852415,0.));
+#6348=CARTESIAN_POINT('Origin',(-159.181545770614,-142.311168852415,0.));
+#6349=CARTESIAN_POINT('',(-161.181545770614,-142.311168852415,0.));
+#6350=CARTESIAN_POINT('Origin',(-163.181545770614,-140.919301538152,0.));
+#6351=CARTESIAN_POINT('',(-162.853862154795,-138.946328287466,0.));
+#6352=CARTESIAN_POINT('',(-161.181545770614,-140.919301538152,0.));
+#6353=CARTESIAN_POINT('Origin',(-194.181545770614,-120.015430341809,0.));
+#6354=CARTESIAN_POINT('',(-197.817909406978,-129.330840129045,0.));
+#6355=CARTESIAN_POINT('',(-202.438774009064,-125.656191089984,3.));
+#6356=CARTESIAN_POINT('',(-202.438774009064,-125.656191089984,3.));
+#6357=CARTESIAN_POINT('',(-202.508018482043,-125.553467194868,3.));
+#6358=CARTESIAN_POINT('Origin',(-194.181545770614,-120.015430341809,3.));
+#6359=CARTESIAN_POINT('',(-202.508018482043,-125.553467194868,3.));
+#6360=CARTESIAN_POINT('',(-204.181545770614,-120.015430341809,0.));
+#6361=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,0.));
+#6362=CARTESIAN_POINT('Origin',(-204.181545770614,-81.3396263369739,9.97183354067129));
+#6363=CARTESIAN_POINT('',(-204.181545770614,-81.3396263369739,9.97183354067129));
+#6364=CARTESIAN_POINT('Origin',(-204.181545770614,-113.339626336974,9.9718335406713));
+#6365=CARTESIAN_POINT('',(-204.181545770614,-97.3253975946944,9.97183354067129));
+#6366=CARTESIAN_POINT('',(-219.181545770614,-113.339626336974,9.9718335406713));
+#6367=CARTESIAN_POINT('Origin',(-219.181545770614,-97.3396263369739,4.9718335406713));
+#6368=CARTESIAN_POINT('Origin',(-120.237629588674,-105.829566219427,20.));
+#6369=CARTESIAN_POINT('',(-121.737629588674,-105.829566219427,20.));
+#6370=CARTESIAN_POINT('Origin',(-120.237629588674,-105.829566219427,20.));
+#6371=CARTESIAN_POINT('',(-121.737629588674,-105.829566219427,13.));
+#6372=CARTESIAN_POINT('',(-121.737629588674,-105.829566219427,20.));
+#6373=CARTESIAN_POINT('Origin',(-120.237629588674,-105.829566219427,13.));
+#6374=CARTESIAN_POINT('Origin',(-120.237629588674,-105.829566219427,13.));
+#6375=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,20.));
+#6376=CARTESIAN_POINT('',(-74.6315457706143,-105.829566219427,13.));
+#6377=CARTESIAN_POINT('',(-74.6315457706143,-105.829566219427,20.));
+#6378=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,13.));
+#6379=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,13.));
+#6380=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,20.));
+#6381=CARTESIAN_POINT('',(-121.631545770614,-94.4295662194267,20.));
+#6382=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,20.));
+#6383=CARTESIAN_POINT('',(-121.631545770614,-94.4295662194267,13.));
+#6384=CARTESIAN_POINT('',(-121.631545770614,-94.4295662194267,20.));
+#6385=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,13.));
+#6386=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,13.));
+#6387=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.1254091990418,20.));
+#6388=CARTESIAN_POINT('',(-74.6315457706143,-94.1254091990418,20.));
+#6389=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.1254091990418,20.));
+#6390=CARTESIAN_POINT('',(-74.6315457706143,-94.1254091990418,13.));
+#6391=CARTESIAN_POINT('',(-74.6315457706143,-94.1254091990418,20.));
+#6392=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.1254091990418,13.));
+#6393=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.1254091990418,13.));
+#6394=CARTESIAN_POINT('Ctrl Pts',(-123.559587646219,-105.830041024796,13.5541264686837));
+#6395=CARTESIAN_POINT('Ctrl Pts',(-123.559444046829,-106.849964906254,13.5541256681211));
+#6396=CARTESIAN_POINT('Ctrl Pts',(-122.567397055623,-108.880416858429,13.5490338503266));
+#6397=CARTESIAN_POINT('Ctrl Pts',(-119.279795562324,-109.577433318998,13.5265663344254));
+#6398=CARTESIAN_POINT('Ctrl Pts',(-116.700322848389,-107.480799091726,13.5041220259831));
+#6399=CARTESIAN_POINT('Ctrl Pts',(-116.708897331878,-104.180057870819,13.5041934161346));
+#6400=CARTESIAN_POINT('Ctrl Pts',(-119.278006074803,-102.071053190586,13.5266429428872));
+#6401=CARTESIAN_POINT('Ctrl Pts',(-122.567816226551,-102.786114656273,13.5489666115339));
+#6402=CARTESIAN_POINT('Ctrl Pts',(-123.55973124561,-104.810117143338,13.5541272692462));
+#6403=CARTESIAN_POINT('Ctrl Pts',(-123.559587646219,-105.830041024796,13.5541264686837));
+#6404=CARTESIAN_POINT('Ctrl Pts',(-123.281214231834,-105.830003052899,13.0905252365177));
+#6405=CARTESIAN_POINT('Ctrl Pts',(-123.281083273223,-106.768142376669,13.0905253121338));
+#6406=CARTESIAN_POINT('Ctrl Pts',(-122.379608427007,-108.637663399542,13.0913321737595));
+#6407=CARTESIAN_POINT('Ctrl Pts',(-119.34434893481,-109.316375858411,13.0908203727355));
+#6408=CARTESIAN_POINT('Ctrl Pts',(-116.918163036604,-107.379040896184,13.0875286369036));
+#6409=CARTESIAN_POINT('Ctrl Pts',(-116.9260734323,-104.282213606569,13.0875519797931));
+#6410=CARTESIAN_POINT('Ctrl Pts',(-119.343658010322,-102.333049608063,13.0908610414229));
+#6411=CARTESIAN_POINT('Ctrl Pts',(-122.379499698355,-103.027814798532,13.0912906834956));
+#6412=CARTESIAN_POINT('Ctrl Pts',(-123.281345190446,-104.891863729129,13.0905251609017));
+#6413=CARTESIAN_POINT('Ctrl Pts',(-123.281214231834,-105.830003052899,13.0905252365177));
+#6414=CARTESIAN_POINT('Ctrl Pts',(-123.131545741644,-105.82998313972,12.5505284737704));
+#6415=CARTESIAN_POINT('Ctrl Pts',(-123.131421319479,-106.725342233994,12.5505300570242));
+#6416=CARTESIAN_POINT('Ctrl Pts',(-122.276689506317,-108.51033619852,12.5616324606859));
+#6417=CARTESIAN_POINT('Ctrl Pts',(-119.3750738324,-109.176650391933,12.596535208705));
+#6418=CARTESIAN_POINT('Ctrl Pts',(-117.033153566363,-107.323677317723,12.6215733819344));
+#6419=CARTESIAN_POINT('Ctrl Pts',(-117.040769887524,-104.33774949764,12.6214995102301));
+#6420=CARTESIAN_POINT('Ctrl Pts',(-119.374842222775,-102.473219889541,12.5965880405589));
+#6421=CARTESIAN_POINT('Ctrl Pts',(-122.276343085146,-103.154646702726,12.5616107418582));
+#6422=CARTESIAN_POINT('Ctrl Pts',(-123.131670163809,-104.934624045445,12.5505268905166));
+#6423=CARTESIAN_POINT('Ctrl Pts',(-123.131545741644,-105.82998313972,12.5505284737704));
+#6424=CARTESIAN_POINT('Ctrl Pts',(-123.131545741514,-105.82998407443,12.009771724628));
+#6425=CARTESIAN_POINT('Ctrl Pts',(-123.131420720763,-106.727573538055,12.0097748276347));
+#6426=CARTESIAN_POINT('Ctrl Pts',(-122.271895563567,-108.516028169182,12.0312392777012));
+#6427=CARTESIAN_POINT('Ctrl Pts',(-119.36765556326,-109.17447999422,12.1017756450497));
+#6428=CARTESIAN_POINT('Ctrl Pts',(-117.033141643741,-107.320203681973,12.1552713161958));
+#6429=CARTESIAN_POINT('Ctrl Pts',(-117.040872104129,-104.341114815609,12.1550931244453));
+#6430=CARTESIAN_POINT('Ctrl Pts',(-119.36711215029,-102.475289344013,12.1018472275461));
+#6431=CARTESIAN_POINT('Ctrl Pts',(-122.271702610538,-103.149101983564,12.0312391876746));
+#6432=CARTESIAN_POINT('Ctrl Pts',(-123.131670762264,-104.932394610805,12.0097686216213));
+#6433=CARTESIAN_POINT('Ctrl Pts',(-123.131545741514,-105.82998407443,12.009771724628));
+#6434=CARTESIAN_POINT('',(-123.131545741514,-105.82998407443,12.009771724628));
+#6435=CARTESIAN_POINT('Origin',(-126.131545712413,-105.830401929433,12.009771724628));
+#6436=CARTESIAN_POINT('Ctrl Pts',(-123.559587660793,-105.829921345877,13.5541264687657));
+#6437=CARTESIAN_POINT('Ctrl Pts',(-123.559587672955,-105.829802970481,13.5541264688352));
+#6438=CARTESIAN_POINT('Ctrl Pts',(-123.559587678435,-105.829684595192,13.5541264688699));
+#6439=CARTESIAN_POINT('Ctrl Pts',(-123.559587677232,-105.82956622001,13.5541264688699));
+#6440=CARTESIAN_POINT('Ctrl Pts',(-123.131545741514,-105.82998407443,12.009771724628));
+#6441=CARTESIAN_POINT('Ctrl Pts',(-123.131420720763,-106.727573538055,12.0097748276347));
+#6442=CARTESIAN_POINT('Ctrl Pts',(-122.271895563567,-108.516028169182,12.0312392777012));
+#6443=CARTESIAN_POINT('Ctrl Pts',(-119.36765556326,-109.17447999422,12.1017756450497));
+#6444=CARTESIAN_POINT('Ctrl Pts',(-117.033141643741,-107.320203681973,12.1552713161958));
+#6445=CARTESIAN_POINT('Ctrl Pts',(-117.040872104129,-104.341114815609,12.1550931244453));
+#6446=CARTESIAN_POINT('Ctrl Pts',(-119.36711215029,-102.475289344013,12.1018472275461));
+#6447=CARTESIAN_POINT('Ctrl Pts',(-122.271552368919,-103.149067130216,12.0312428399162));
+#6448=CARTESIAN_POINT('Ctrl Pts',(-123.131537308737,-104.932117893314,12.0097719535077));
+#6449=CARTESIAN_POINT('Ctrl Pts',(-123.131545768645,-105.829566219861,12.0097717239592));
+#6450=CARTESIAN_POINT('Ctrl Pts',(-123.559587679644,-105.829566219426,13.5541264688696));
+#6451=CARTESIAN_POINT('Ctrl Pts',(-123.559587679644,-105.829684594516,13.5541264688696));
+#6452=CARTESIAN_POINT('Ctrl Pts',(-123.559587673408,-105.829802969987,13.5541264688291));
+#6453=CARTESIAN_POINT('Ctrl Pts',(-123.559587660935,-105.82992134584,13.554126468748));
+#6454=CARTESIAN_POINT('Ctrl Pts',(-123.837961096962,-105.829566219426,14.0177277012403));
+#6455=CARTESIAN_POINT('Ctrl Pts',(-123.837961096962,-105.82969738298,14.0177277012403));
+#6456=CARTESIAN_POINT('Ctrl Pts',(-123.837961089837,-105.82982846806,14.0177277011588));
+#6457=CARTESIAN_POINT('Ctrl Pts',(-123.837961075575,-105.829959632459,14.0177277009962));
+#6458=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-105.829566219426,14.5577244643385));
+#6459=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-105.829705639201,14.5577244643385));
+#6460=CARTESIAN_POINT('Ctrl Pts',(-123.987629580908,-105.829844977656,14.5577244641958));
+#6461=CARTESIAN_POINT('Ctrl Pts',(-123.987629565366,-105.829984398329,14.5577244639107));
+#6462=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-105.829566219427,15.0984812138343));
+#6463=CARTESIAN_POINT('Ctrl Pts',(-123.987629588674,-105.829708204019,15.0984812138343));
+#6464=CARTESIAN_POINT('Ctrl Pts',(-123.98762958061,-105.82985018907,15.0984812136301));
+#6465=CARTESIAN_POINT('Ctrl Pts',(-123.987629564482,-105.829992174578,15.0984812132217));
+#6466=CARTESIAN_POINT('Origin',(-120.131545770614,-105.829566219427,3.));
+#6467=CARTESIAN_POINT('',(-123.131545770614,-105.829566219427,3.));
+#6468=CARTESIAN_POINT('',(-123.131545770614,-105.829566219427,3.));
+#6469=CARTESIAN_POINT('Origin',(-120.131545770614,-105.829566219427,3.));
+#6470=CARTESIAN_POINT('Origin',(-120.237629588674,-105.829566219427,13.));
+#6471=CARTESIAN_POINT('',(-123.987629588674,-105.829566219427,20.));
+#6472=CARTESIAN_POINT('',(-123.987629588674,-105.829566219427,13.));
+#6473=CARTESIAN_POINT('Origin',(-120.237629588674,-105.829566219427,20.));
+#6474=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,12.0795759736429));
+#6475=CARTESIAN_POINT('',(-123.131545770614,-94.4295662194267,12.0795759736429));
+#6476=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,12.0795759736429));
+#6477=CARTESIAN_POINT('',(-123.506545770614,-94.4295662194267,13.5319447284707));
+#6478=CARTESIAN_POINT('Origin',(-126.131545770614,-94.4295662194267,12.0795759736429));
+#6479=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,13.5319447284707));
+#6480=CARTESIAN_POINT('Ctrl Pts',(-123.506545770614,-94.4295662194267,13.5319447284707));
+#6481=CARTESIAN_POINT('Ctrl Pts',(-123.506545770614,-91.0545662194267,13.5319447284707));
+#6482=CARTESIAN_POINT('Ctrl Pts',(-120.131545770614,-91.0545662194267,13.5319447284707));
+#6483=CARTESIAN_POINT('Ctrl Pts',(-116.756545770614,-91.0545662194267,13.5319447284707));
+#6484=CARTESIAN_POINT('Ctrl Pts',(-116.756545770614,-94.4295662194267,13.5319447284707));
+#6485=CARTESIAN_POINT('Ctrl Pts',(-116.756545770614,-97.8045662194267,13.5319447284707));
+#6486=CARTESIAN_POINT('Ctrl Pts',(-120.131545770614,-97.8045662194267,13.5319447284707));
+#6487=CARTESIAN_POINT('Ctrl Pts',(-123.506545770614,-97.8045662194267,13.5319447284707));
+#6488=CARTESIAN_POINT('Ctrl Pts',(-123.506545770614,-94.4295662194267,13.5319447284707));
+#6489=CARTESIAN_POINT('Ctrl Pts',(-123.881545770614,-94.4295662194267,14.209716814057));
+#6490=CARTESIAN_POINT('Ctrl Pts',(-123.881545770614,-90.6795662194266,14.209716814057));
+#6491=CARTESIAN_POINT('Ctrl Pts',(-120.131545770614,-90.6795662194266,14.209716814057));
+#6492=CARTESIAN_POINT('Ctrl Pts',(-116.381545770614,-90.6795662194266,14.209716814057));
+#6493=CARTESIAN_POINT('Ctrl Pts',(-116.381545770614,-94.4295662194267,14.209716814057));
+#6494=CARTESIAN_POINT('Ctrl Pts',(-116.381545770614,-98.1795662194267,14.209716814057));
+#6495=CARTESIAN_POINT('Ctrl Pts',(-120.131545770614,-98.1795662194267,14.209716814057));
+#6496=CARTESIAN_POINT('Ctrl Pts',(-123.881545770614,-98.1795662194267,14.209716814057));
+#6497=CARTESIAN_POINT('Ctrl Pts',(-123.881545770614,-94.4295662194267,14.209716814057));
+#6498=CARTESIAN_POINT('Ctrl Pts',(-123.881545770614,-94.4295662194267,14.9843134832985));
+#6499=CARTESIAN_POINT('Ctrl Pts',(-123.881545770614,-90.6795662194266,14.9843134832985));
+#6500=CARTESIAN_POINT('Ctrl Pts',(-120.131545770614,-90.6795662194266,14.9843134832985));
+#6501=CARTESIAN_POINT('Ctrl Pts',(-116.381545770614,-90.6795662194266,14.9843134832985));
+#6502=CARTESIAN_POINT('Ctrl Pts',(-116.381545770614,-94.4295662194267,14.9843134832985));
+#6503=CARTESIAN_POINT('Ctrl Pts',(-116.381545770614,-98.1795662194267,14.9843134832985));
+#6504=CARTESIAN_POINT('Ctrl Pts',(-120.131545770614,-98.1795662194267,14.9843134832985));
+#6505=CARTESIAN_POINT('Ctrl Pts',(-123.881545770614,-98.1795662194267,14.9843134832985));
+#6506=CARTESIAN_POINT('Ctrl Pts',(-123.881545770614,-94.4295662194267,14.9843134832985));
+#6507=CARTESIAN_POINT('',(-123.881545770614,-94.4295662194267,14.9843134832985));
+#6508=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,14.9843134832985));
+#6509=CARTESIAN_POINT('Origin',(-120.881545770614,-94.4295662194267,14.9843134832985));
+#6510=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,3.));
+#6511=CARTESIAN_POINT('',(-123.131545770614,-94.4295662194267,3.));
+#6512=CARTESIAN_POINT('',(-123.131545770614,-94.4295662194267,3.));
+#6513=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,3.));
+#6514=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,13.));
+#6515=CARTESIAN_POINT('',(-123.881545770614,-94.4295662194267,20.));
+#6516=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,20.));
+#6517=CARTESIAN_POINT('',(-123.881545770614,-94.4295662194267,13.));
+#6518=CARTESIAN_POINT('Ctrl Pts',(-76.3636041579496,-95.2044951210279,13.5145137504456));
+#6519=CARTESIAN_POINT('Ctrl Pts',(-76.0877732831646,-96.1687403549425,13.4891692862341));
+#6520=CARTESIAN_POINT('Ctrl Pts',(-74.6471789346414,-97.7906462781541,13.434495115642));
+#6521=CARTESIAN_POINT('Ctrl Pts',(-71.452088668253,-97.7147996373169,13.4358555929888));
+#6522=CARTESIAN_POINT('Ctrl Pts',(-69.3922647902795,-95.1761923615681,13.5240412187873));
+#6523=CARTESIAN_POINT('Ctrl Pts',(-70.0993398121974,-91.8589665511421,13.581328663742));
+#6524=CARTESIAN_POINT('Ctrl Pts',(-72.4422614372934,-90.7539225047553,13.5853460271631));
+#6525=CARTESIAN_POINT('Ctrl Pts',(-74.5088577284812,-91.0562359670048,13.5837030507885));
+#6526=CARTESIAN_POINT('Ctrl Pts',(-76.3199947506878,-92.2978272726961,13.5742157910112));
+#6527=CARTESIAN_POINT('Ctrl Pts',(-76.6394350327531,-94.2402498870491,13.5398582146589));
+#6528=CARTESIAN_POINT('Ctrl Pts',(-76.3636041579496,-95.204495121028,13.5145137504456));
+#6529=CARTESIAN_POINT('Ctrl Pts',(-76.1550778517666,-95.1658913246917,13.0966831884058));
+#6530=CARTESIAN_POINT('Ctrl Pts',(-75.9184720000272,-96.0721509999161,13.0929818620397));
+#6531=CARTESIAN_POINT('Ctrl Pts',(-74.5859986035885,-97.6386203692236,13.078562358379));
+#6532=CARTESIAN_POINT('Ctrl Pts',(-71.5199481008517,-97.5653638348158,13.0788824571275));
+#6533=CARTESIAN_POINT('Ctrl Pts',(-69.6281671719808,-95.1131045107672,13.1021518312341));
+#6534=CARTESIAN_POINT('Ctrl Pts',(-70.378040045419,-92.0799311492505,13.0967525620814));
+#6535=CARTESIAN_POINT('Ctrl Pts',(-72.5070541927437,-91.1139060666565,13.0876526176552));
+#6536=CARTESIAN_POINT('Ctrl Pts',(-74.3802694905074,-91.3796779886611,13.0898491783234));
+#6537=CARTESIAN_POINT('Ctrl Pts',(-76.0419140218505,-92.4788205061776,13.0977282517518));
+#6538=CARTESIAN_POINT('Ctrl Pts',(-76.391683703522,-94.2596316494059,13.100384514772));
+#6539=CARTESIAN_POINT('Ctrl Pts',(-76.1550778517666,-95.1658913246917,13.0966831884058));
+#6540=CARTESIAN_POINT('Ctrl Pts',(-76.0429275671437,-95.153514339792,12.6287489863598));
+#6541=CARTESIAN_POINT('Ctrl Pts',(-75.8257904861372,-96.0271507478558,12.6568087329316));
+#6542=CARTESIAN_POINT('Ctrl Pts',(-74.5513236344477,-97.5594280781324,12.6950091874605));
+#6543=CARTESIAN_POINT('Ctrl Pts',(-71.5584506586311,-97.4871825940967,12.6940541329558));
+#6544=CARTESIAN_POINT('Ctrl Pts',(-69.7560629844549,-95.0896654914844,12.6323113471167));
+#6545=CARTESIAN_POINT('Ctrl Pts',(-70.5201605710967,-92.2073747354178,12.5220134251879));
+#6546=CARTESIAN_POINT('Ctrl Pts',(-72.5397707071304,-91.3094903471421,12.4831796924753));
+#6547=CARTESIAN_POINT('Ctrl Pts',(-74.3150704558629,-91.5572608199803,12.4936702764254));
+#6548=CARTESIAN_POINT('Ctrl Pts',(-75.8990663395542,-92.5852285382366,12.5369337953366));
+#6549=CARTESIAN_POINT('Ctrl Pts',(-76.2600646481651,-94.2798779316681,12.6006892397861));
+#6550=CARTESIAN_POINT('Ctrl Pts',(-76.0429275671436,-95.153514339792,12.6287489863598));
+#6551=CARTESIAN_POINT('Ctrl Pts',(-76.0390724602241,-95.1686795728487,12.160442456517));
+#6552=CARTESIAN_POINT('Ctrl Pts',(-75.8179952099063,-96.0383540318318,12.2204078483989));
+#6553=CARTESIAN_POINT('Ctrl Pts',(-74.5450785027239,-97.5589622636744,12.3113347612408));
+#6554=CARTESIAN_POINT('Ctrl Pts',(-71.5654459977456,-97.485635170065,12.3090985601992));
+#6555=CARTESIAN_POINT('Ctrl Pts',(-69.7635876112212,-95.1103778826632,12.1621886835608));
+#6556=CARTESIAN_POINT('Ctrl Pts',(-70.5024259425863,-92.2234198306637,11.946287986631));
+#6557=CARTESIAN_POINT('Ctrl Pts',(-72.5345114561711,-91.3063682805594,11.8773188469271));
+#6558=CARTESIAN_POINT('Ctrl Pts',(-74.3245988460918,-91.5589122172898,11.8962125804259));
+#6559=CARTESIAN_POINT('Ctrl Pts',(-75.9135855446055,-92.6024607027588,11.9752709193251));
+#6560=CARTESIAN_POINT('Ctrl Pts',(-76.2601497105573,-94.2990051138049,12.100477064631));
+#6561=CARTESIAN_POINT('Ctrl Pts',(-76.0390724602241,-95.1686795728487,12.160442456517));
+#6562=CARTESIAN_POINT('',(-76.3636041579497,-95.2044951210279,13.5145137504456));
+#6563=CARTESIAN_POINT('',(-76.0390724602241,-95.1686795728487,12.160442456517));
+#6564=CARTESIAN_POINT('Origin',(-78.9465991498339,-95.9077929262707,12.160442456517));
+#6565=CARTESIAN_POINT('',(-76.1279703189321,-94.4294540404638,12.1085007451299));
+#6566=CARTESIAN_POINT('Ctrl Pts',(-76.0390724602241,-95.1686795728487,12.160442456517));
+#6567=CARTESIAN_POINT('Ctrl Pts',(-75.8179952099063,-96.0383540318318,12.2204078483989));
+#6568=CARTESIAN_POINT('Ctrl Pts',(-74.5450785027239,-97.5589622636744,12.3113347612408));
+#6569=CARTESIAN_POINT('Ctrl Pts',(-71.5654459977456,-97.485635170065,12.3090985601992));
+#6570=CARTESIAN_POINT('Ctrl Pts',(-69.7635876112212,-95.1103778826632,12.1621886835608));
+#6571=CARTESIAN_POINT('Ctrl Pts',(-70.5024259425863,-92.2234198306637,11.946287986631));
+#6572=CARTESIAN_POINT('Ctrl Pts',(-72.5345114561711,-91.3063682805594,11.8773188469271));
+#6573=CARTESIAN_POINT('Ctrl Pts',(-74.3245988460918,-91.5589122172898,11.8962125804259));
+#6574=CARTESIAN_POINT('Ctrl Pts',(-75.6931816612937,-92.4577130224688,11.9643049591205));
+#6575=CARTESIAN_POINT('Ctrl Pts',(-76.124043239364,-93.7808115252115,12.0621890828684));
+#6576=CARTESIAN_POINT('Ctrl Pts',(-76.1279703189321,-94.4294540404638,12.1085007451299));
+#6577=CARTESIAN_POINT('Ctrl Pts',(-76.1279703189321,-94.4294540404638,12.1085007451299));
+#6578=CARTESIAN_POINT('Ctrl Pts',(-76.1294779995955,-94.6784802597612,12.1262806745844));
+#6579=CARTESIAN_POINT('Ctrl Pts',(-76.1004024695072,-94.9274193682546,12.1438071942478));
+#6580=CARTESIAN_POINT('Ctrl Pts',(-76.0390724602241,-95.1686795728487,12.160442456517));
+#6581=CARTESIAN_POINT('Ctrl Pts',(-76.3636041579496,-95.204495121028,13.5145137504456));
+#6582=CARTESIAN_POINT('Ctrl Pts',(-76.4287600156519,-94.9767242984177,13.5205005360257));
+#6583=CARTESIAN_POINT('Ctrl Pts',(-76.4683396957657,-94.740823071115,13.5261686259206));
+#6584=CARTESIAN_POINT('Ctrl Pts',(-76.4829390554398,-94.5023961897666,13.5314811596678));
+#6585=CARTESIAN_POINT('Ctrl Pts',(-76.0333073480428,-92.5670372854434,13.5668794147336));
+#6586=CARTESIAN_POINT('Ctrl Pts',(-75.9804241369791,-92.47528263198,13.568214496451));
+#6587=CARTESIAN_POINT('Ctrl Pts',(-75.9230380754552,-92.3860644418608,13.569461021482));
+#6588=CARTESIAN_POINT('Ctrl Pts',(-75.8611997349265,-92.2998584002369,13.5706158614135));
+#6589=CARTESIAN_POINT('Ctrl Pts',(-75.4144262395845,-91.6770316198504,13.5789594208998));
+#6590=CARTESIAN_POINT('Ctrl Pts',(-74.7352498562571,-91.2114348802162,13.5825171433164));
+#6591=CARTESIAN_POINT('Ctrl Pts',(-73.9842255535286,-91.01001003405,13.5838686610258));
+#6592=CARTESIAN_POINT('Ctrl Pts',(-73.7338841192858,-90.9428684186612,13.584319166929));
+#6593=CARTESIAN_POINT('Ctrl Pts',(-73.4755595828873,-90.9050792358801,13.5845245389758));
+#6594=CARTESIAN_POINT('Ctrl Pts',(-73.2168350287664,-90.8994044240193,13.5845995618706));
+#6595=CARTESIAN_POINT('Ctrl Pts',(-72.1819368122827,-90.8767051765761,13.5848996534496));
+#6596=CARTESIAN_POINT('Ctrl Pts',(-71.14063831224,-91.3678358638591,13.5831141585958));
+#6597=CARTESIAN_POINT('Ctrl Pts',(-70.5021432252324,-92.1662721759049,13.5726735036765));
+#6598=CARTESIAN_POINT('Ctrl Pts',(-69.8636481382247,-92.9647084879507,13.5622328487571));
+#6599=CARTESIAN_POINT('Ctrl Pts',(-69.6279564642521,-94.0704504247594,13.5431370337722));
+#6600=CARTESIAN_POINT('Ctrl Pts',(-69.853414606928,-95.0464226057885,13.51889152198));
+#6601=CARTESIAN_POINT('Ctrl Pts',(-70.078872749604,-96.0223947868177,13.4946460101878));
+#6602=CARTESIAN_POINT('Ctrl Pts',(-70.7654807089285,-96.8685972120673,13.4652508015883));
+#6603=CARTESIAN_POINT('Ctrl Pts',(-71.6412997329888,-97.3043395314983,13.4503264510641));
+#6604=CARTESIAN_POINT('Ctrl Pts',(-72.5171187570491,-97.7400818509294,13.4354021005399));
+#6605=CARTESIAN_POINT('Ctrl Pts',(-73.5821488458453,-97.7653640645417,13.4349486080909));
+#6606=CARTESIAN_POINT('Ctrl Pts',(-74.4748124773741,-97.372528690545,13.4483904045145));
+#6607=CARTESIAN_POINT('Ctrl Pts',(-75.367476108903,-96.9796933165483,13.461832200938));
+#6608=CARTESIAN_POINT('Ctrl Pts',(-76.0877732831646,-96.1687403549425,13.4891692862341));
+#6609=CARTESIAN_POINT('Ctrl Pts',(-76.3636041579497,-95.2044951210279,13.5145137504456));
+#6610=CARTESIAN_POINT('Ctrl Pts',(-76.4702086772714,-94.4823325901826,13.4999066694216));
+#6611=CARTESIAN_POINT('Ctrl Pts',(-76.4455856273119,-94.8930649620195,13.4912619957933));
+#6612=CARTESIAN_POINT('Ctrl Pts',(-76.2383152362771,-95.7401181643648,13.4734390935678));
+#6613=CARTESIAN_POINT('Ctrl Pts',(-75.3856074220547,-96.9483591866352,13.4500421276376));
+#6614=CARTESIAN_POINT('Ctrl Pts',(-74.1054321010255,-97.6001460799383,13.4391965752889));
+#6615=CARTESIAN_POINT('Ctrl Pts',(-72.7364094358691,-97.6854030333387,13.4378100204226));
+#6616=CARTESIAN_POINT('Ctrl Pts',(-71.9709829041676,-97.4840842481893,13.4410883873508));
+#6617=CARTESIAN_POINT('Ctrl Pts',(-71.4069770200703,-97.1727361643644,13.4465073078461));
+#6618=CARTESIAN_POINT('Ctrl Pts',(-71.0905035971405,-96.9617019545075,13.450255439204));
+#6619=CARTESIAN_POINT('Ctrl Pts',(-70.6118835563479,-96.5432437188274,13.4579207181987));
+#6620=CARTESIAN_POINT('Ctrl Pts',(-70.1407560241824,-95.8777861536192,13.470839250199));
+#6621=CARTESIAN_POINT('Ctrl Pts',(-69.6394827068693,-94.4847765005184,13.4997116786602));
+#6622=CARTESIAN_POINT('Ctrl Pts',(-69.9455012001574,-92.5424292764986,13.5409860326448));
+#6623=CARTESIAN_POINT('Ctrl Pts',(-71.255957917942,-91.3611871864228,13.5619891765931));
+#6624=CARTESIAN_POINT('Ctrl Pts',(-72.1895639047742,-91.0431701810422,13.5674733572201));
+#6625=CARTESIAN_POINT('Ctrl Pts',(-72.574165554003,-90.9480599028014,13.5690980449072));
+#6626=CARTESIAN_POINT('Ctrl Pts',(-73.2604874104373,-90.8735985116919,13.570344141914));
+#6627=CARTESIAN_POINT('Ctrl Pts',(-74.6508121862682,-91.0929975282536,13.5667021704588));
+#6628=CARTESIAN_POINT('Ctrl Pts',(-75.6133344361633,-91.886486143142,13.5527171754737));
+#6629=CARTESIAN_POINT('Ctrl Pts',(-76.0129392406345,-92.5686818622352,13.5392955626975));
+#6630=CARTESIAN_POINT('Ctrl Pts',(-76.6936557426358,-94.7681124915674,13.9302459139557));
+#6631=CARTESIAN_POINT('Ctrl Pts',(-76.6212898780559,-95.210411065392,13.9126633879333));
+#6632=CARTESIAN_POINT('Ctrl Pts',(-76.3030039121416,-96.0875413905943,13.8758299488947));
+#6633=CARTESIAN_POINT('Ctrl Pts',(-75.3113454334661,-97.2150963996212,13.8249048882077));
+#6634=CARTESIAN_POINT('Ctrl Pts',(-74.051825497356,-97.7570303424566,13.7997423258759));
+#6635=CARTESIAN_POINT('Ctrl Pts',(-72.7576180060479,-97.8268831107782,13.7965058634988));
+#6636=CARTESIAN_POINT('Ctrl Pts',(-72.0279284264069,-97.662171097034,13.8041665285438));
+#6637=CARTESIAN_POINT('Ctrl Pts',(-71.463861334367,-97.3947326886447,13.8164976351834));
+#6638=CARTESIAN_POINT('Ctrl Pts',(-71.1413282877171,-97.2105270833858,13.8249526880793));
+#6639=CARTESIAN_POINT('Ctrl Pts',(-70.635554105885,-96.8369374268656,13.8420314230501));
+#6640=CARTESIAN_POINT('Ctrl Pts',(-70.0920709429032,-96.2104361244137,13.8700318889511));
+#6641=CARTESIAN_POINT('Ctrl Pts',(-69.4072311784394,-94.8099890730742,13.9305125308076));
+#6642=CARTESIAN_POINT('Ctrl Pts',(-69.5074587511013,-92.6029917011034,14.0124865542995));
+#6643=CARTESIAN_POINT('Ctrl Pts',(-70.9534987164858,-91.1267402841017,14.0534914896032));
+#6644=CARTESIAN_POINT('Ctrl Pts',(-72.0329333009112,-90.7286107361449,14.0642711179276));
+#6645=CARTESIAN_POINT('Ctrl Pts',(-72.4797887210584,-90.6088428823677,14.0674524309976));
+#6646=CARTESIAN_POINT('Ctrl Pts',(-73.281317024415,-90.5150032275926,14.069907825751));
+#6647=CARTESIAN_POINT('Ctrl Pts',(-74.9085268535257,-90.7920684130076,14.062747520642));
+#6648=CARTESIAN_POINT('Ctrl Pts',(-75.9802570733551,-91.7849492941067,14.0354431986488));
+#6649=CARTESIAN_POINT('Ctrl Pts',(-76.3752169567351,-92.5958036412783,14.0090007060734));
+#6650=CARTESIAN_POINT('Ctrl Pts',(-76.774605130229,-95.0465502924727,14.4382378202102));
+#6651=CARTESIAN_POINT('Ctrl Pts',(-76.6594879196955,-95.5032114637689,14.4069867039941));
+#6652=CARTESIAN_POINT('Ctrl Pts',(-76.2494029894516,-96.3777688330273,14.3401551538761));
+#6653=CARTESIAN_POINT('Ctrl Pts',(-75.1755390902543,-97.4006986278755,14.2417158442791));
+#6654=CARTESIAN_POINT('Ctrl Pts',(-73.978373540029,-97.8419814881727,14.1897963080023));
+#6655=CARTESIAN_POINT('Ctrl Pts',(-72.7873162366431,-97.8982674077714,14.1830835074312));
+#6656=CARTESIAN_POINT('Ctrl Pts',(-72.1112361968373,-97.7660160267861,14.1989971550277));
+#6657=CARTESIAN_POINT('Ctrl Pts',(-71.5670492342555,-97.5410372742135,14.2239787583727));
+#6658=CARTESIAN_POINT('Ctrl Pts',(-71.2509717690611,-97.3836644447635,14.2409601181248));
+#6659=CARTESIAN_POINT('Ctrl Pts',(-70.7407068580192,-97.0578425057754,14.2748195787053));
+#6660=CARTESIAN_POINT('Ctrl Pts',(-70.1544510382147,-96.4838351286337,14.3286927544215));
+#6661=CARTESIAN_POINT('Ctrl Pts',(-69.3278776277,-95.1237151904264,14.440356439856));
+#6662=CARTESIAN_POINT('Ctrl Pts',(-69.2188878147814,-92.7439134154944,14.5811433558005));
+#6663=CARTESIAN_POINT('Ctrl Pts',(-70.7392103005745,-91.0283003925618,14.6497073121466));
+#6664=CARTESIAN_POINT('Ctrl Pts',(-71.9208635967241,-90.5653316716782,14.6679093150339));
+#6665=CARTESIAN_POINT('Ctrl Pts',(-72.4118822343336,-90.4254460797092,14.6732634244851));
+#6666=CARTESIAN_POINT('Ctrl Pts',(-73.2963380446938,-90.3157985937153,14.6774183728973));
+#6667=CARTESIAN_POINT('Ctrl Pts',(-75.0949966409514,-90.6400187717444,14.6652858155556));
+#6668=CARTESIAN_POINT('Ctrl Pts',(-76.2317503882828,-91.794423305698,14.6194698292065));
+#6669=CARTESIAN_POINT('Ctrl Pts',(-76.6053277600844,-92.7017609358866,14.5745627869104));
+#6670=CARTESIAN_POINT('Ctrl Pts',(-76.7008163416603,-95.2755429263383,14.9470680441145));
+#6671=CARTESIAN_POINT('Ctrl Pts',(-76.554829234023,-95.7285924063033,14.9020560931226));
+#6672=CARTESIAN_POINT('Ctrl Pts',(-76.0860534610163,-96.5725531290205,14.8050219757141));
+#6673=CARTESIAN_POINT('Ctrl Pts',(-74.9920787844687,-97.488050590754,14.6587406275419));
+#6674=CARTESIAN_POINT('Ctrl Pts',(-73.8903060814966,-97.8486976406487,14.5799254553484));
+#6675=CARTESIAN_POINT('Ctrl Pts',(-72.8234701372219,-97.8943610946863,14.5697201699212));
+#6676=CARTESIAN_POINT('Ctrl Pts',(-72.2144033816433,-97.7875303045861,14.5939267895095));
+#6677=CARTESIAN_POINT('Ctrl Pts',(-71.7070931749429,-97.5982369140276,14.6316324682991));
+#6678=CARTESIAN_POINT('Ctrl Pts',(-71.4086105164128,-97.464047118545,14.6571919481499));
+#6679=CARTESIAN_POINT('Ctrl Pts',(-70.9154609896398,-97.1814796521431,14.7079387230444));
+#6680=CARTESIAN_POINT('Ctrl Pts',(-70.3193987048209,-96.6629897627518,14.7878630643723));
+#6681=CARTESIAN_POINT('Ctrl Pts',(-69.4120146419399,-95.3772664662863,14.9510652639633));
+#6682=CARTESIAN_POINT('Ctrl Pts',(-69.1284638058527,-92.9399237416473,15.1510156510297));
+#6683=CARTESIAN_POINT('Ctrl Pts',(-70.6505188798053,-91.0830585523468,15.24727124281));
+#6684=CARTESIAN_POINT('Ctrl Pts',(-71.8730348045448,-90.581995619981,15.2729331013928));
+#6685=CARTESIAN_POINT('Ctrl Pts',(-72.3824250869317,-90.4301318771982,15.2804723939407));
+#6686=CARTESIAN_POINT('Ctrl Pts',(-73.3029822134009,-90.3110745864245,15.2863347358757));
+#6687=CARTESIAN_POINT('Ctrl Pts',(-75.177487115665,-90.6634588207627,15.2691994555561));
+#6688=CARTESIAN_POINT('Ctrl Pts',(-76.3247828645616,-91.9129487607717,15.2047592818758));
+#6689=CARTESIAN_POINT('Ctrl Pts',(-76.6647400788017,-92.8688114190851,15.1412796197671));
+#6690=CARTESIAN_POINT('Ctrl Pts',(-76.6647400788017,-92.8688114190851,15.1412796197671));
+#6691=CARTESIAN_POINT('Ctrl Pts',(-76.6306813984806,-92.7730481308043,15.1476393421912));
+#6692=CARTESIAN_POINT('Ctrl Pts',(-76.5923767985474,-92.6785842893032,15.1537886156333));
+#6693=CARTESIAN_POINT('Ctrl Pts',(-76.5501425752148,-92.58585278084,15.1597181137206));
+#6694=CARTESIAN_POINT('Ctrl Pts',(-76.5264230297835,-92.5337729968556,15.1630482329501));
+#6695=CARTESIAN_POINT('Ctrl Pts',(-76.501464896381,-92.4822392479473,15.1663090778671));
+#6696=CARTESIAN_POINT('Ctrl Pts',(-76.4753303938334,-92.4313246787405,15.16949935442));
+#6697=CARTESIAN_POINT('Ctrl Pts',(-76.4613974204461,-92.4041808164655,15.1712001726479));
+#6698=CARTESIAN_POINT('Ctrl Pts',(-76.447130167345,-92.3772128910891,15.1728809381069));
+#6699=CARTESIAN_POINT('Ctrl Pts',(-76.4325385272922,-92.3504316273656,15.1745414847529));
+#6700=CARTESIAN_POINT('Ctrl Pts',(-76.4237463057263,-92.3342945239544,15.1755420504179));
+#6701=CARTESIAN_POINT('Ctrl Pts',(-76.4148363154125,-92.3182251865731,15.1765352756638));
+#6702=CARTESIAN_POINT('Ctrl Pts',(-76.4058107736756,-92.3022259135684,15.1775211278309));
+#6703=CARTESIAN_POINT('Ctrl Pts',(-76.3998715513014,-92.2916976546595,15.1781698639865));
+#6704=CARTESIAN_POINT('Ctrl Pts',(-76.3938774577436,-92.2811911490753,15.1788159366335));
+#6705=CARTESIAN_POINT('Ctrl Pts',(-76.3878277801632,-92.2707053093954,15.1794594366597));
+#6706=CARTESIAN_POINT('Ctrl Pts',(-76.3368637153135,-92.1823698557531,15.1848804490408));
+#6707=CARTESIAN_POINT('Ctrl Pts',(-76.2819752201276,-92.0955456232374,15.1901160016666));
+#6708=CARTESIAN_POINT('Ctrl Pts',(-76.2233975576719,-92.0106964129648,15.195152761043));
+#6709=CARTESIAN_POINT('Ctrl Pts',(-76.1643834773183,-91.925215055344,15.2002270455074));
+#6710=CARTESIAN_POINT('Ctrl Pts',(-76.1016254112111,-91.8417389123522,15.2050995551758));
+#6711=CARTESIAN_POINT('Ctrl Pts',(-76.035414015373,-91.760723764591,15.2097592101422));
+#6712=CARTESIAN_POINT('Ctrl Pts',(-75.969222536624,-91.6797329870442,15.2144174634351));
+#6713=CARTESIAN_POINT('Ctrl Pts',(-75.8995802606592,-91.6012023571915,15.2188629861788));
+#6714=CARTESIAN_POINT('Ctrl Pts',(-75.8268212474486,-91.5255592017617,15.2230873388659));
+#6715=CARTESIAN_POINT('Ctrl Pts',(-75.7546517359131,-91.4505289156505,15.2272774653743));
+#6716=CARTESIAN_POINT('Ctrl Pts',(-75.6794162954785,-91.3783400546622,15.2312499921552));
+#6717=CARTESIAN_POINT('Ctrl Pts',(-75.6014766217214,-91.3093732791638,15.234999288021));
+#6718=CARTESIAN_POINT('Ctrl Pts',(-75.5643086926468,-91.2764843524252,15.2367872549973));
+#6719=CARTESIAN_POINT('Ctrl Pts',(-75.5265262573273,-91.2443275907883,15.2385244940918));
+#6720=CARTESIAN_POINT('Ctrl Pts',(-75.4881709217743,-91.2129407848111,15.2402106044257));
+#6721=CARTESIAN_POINT('Ctrl Pts',(-75.4787171184703,-91.2052045810791,15.2406261960302));
+#6722=CARTESIAN_POINT('Ctrl Pts',(-75.4692285168294,-91.197515142183,15.2410386820996));
+#6723=CARTESIAN_POINT('Ctrl Pts',(-75.4597057524404,-91.1898730108168,15.2414480579));
+#6724=CARTESIAN_POINT('Ctrl Pts',(-75.45029025424,-91.1823169618391,15.2418528224151));
+#6725=CARTESIAN_POINT('Ctrl Pts',(-75.4408352278635,-91.1748022162218,15.2422548113649));
+#6726=CARTESIAN_POINT('Ctrl Pts',(-75.4313363950113,-91.1673257916379,15.2426542048192));
+#6727=CARTESIAN_POINT('Ctrl Pts',(-75.3578177859585,-91.1094601207025,15.2457454110422));
+#6728=CARTESIAN_POINT('Ctrl Pts',(-75.2817624527617,-91.0539655366183,15.2486770167799));
+#6729=CARTESIAN_POINT('Ctrl Pts',(-75.2034314364437,-91.001226598046,15.2514383731441));
+#6730=CARTESIAN_POINT('Ctrl Pts',(-75.1258471477569,-90.948990418464,15.2541734055667));
+#6731=CARTESIAN_POINT('Ctrl Pts',(-75.0460307851958,-90.8994581144677,15.2567414180392));
+#6732=CARTESIAN_POINT('Ctrl Pts',(-74.9642715672777,-90.8529673151432,15.2591346525564));
+#6733=CARTESIAN_POINT('Ctrl Pts',(-74.8840861881292,-90.8073714488216,15.2614818180753));
+#6734=CARTESIAN_POINT('Ctrl Pts',(-74.8020324896796,-90.7647014980501,15.2636608744694));
+#6735=CARTESIAN_POINT('Ctrl Pts',(-74.7184110791853,-90.7252346261918,15.265666971554));
+#6736=CARTESIAN_POINT('Ctrl Pts',(-74.676280491741,-90.7053502151761,15.2666776941447));
+#6737=CARTESIAN_POINT('Ctrl Pts',(-74.6337523566276,-90.6862781796153,15.2676445516491));
+#6738=CARTESIAN_POINT('Ctrl Pts',(-74.5908673154735,-90.668049423238,15.2685671620943));
+#6739=CARTESIAN_POINT('Ctrl Pts',(-74.5043993719039,-90.631295276912,15.2704273964737));
+#6740=CARTESIAN_POINT('Ctrl Pts',(-74.4164799727519,-90.5979725422919,15.2721075878408));
+#6741=CARTESIAN_POINT('Ctrl Pts',(-74.3276233262142,-90.5681245478821,15.2736078764477));
+#6742=CARTESIAN_POINT('Ctrl Pts',(-74.275975370983,-90.550775391245,15.2744799196973));
+#6743=CARTESIAN_POINT('Ctrl Pts',(-74.2240110047005,-90.534599224766,15.2752912312256));
+#6744=CARTESIAN_POINT('Ctrl Pts',(-74.1718320723941,-90.5195965299016,15.2760422397712));
+#6745=CARTESIAN_POINT('Ctrl Pts',(-74.0720530532805,-90.4909076681049,15.2774783537874));
+#6746=CARTESIAN_POINT('Ctrl Pts',(-73.9705592088364,-90.4662450557768,15.2787071974854));
+#6747=CARTESIAN_POINT('Ctrl Pts',(-73.8679131427568,-90.4457732829565,15.2797234041632));
+#6748=CARTESIAN_POINT('Ctrl Pts',(-73.7642537399444,-90.4250994098495,15.2807496429796));
+#6749=CARTESIAN_POINT('Ctrl Pts',(-73.6594200689907,-90.4086997541646,15.2815590201042));
+#6750=CARTESIAN_POINT('Ctrl Pts',(-73.5540146165503,-90.3966954831245,15.2821485443754));
+#6751=CARTESIAN_POINT('Ctrl Pts',(-73.4485895468765,-90.384688977944,15.2827381783642));
+#6752=CARTESIAN_POINT('Ctrl Pts',(-73.3425933691419,-90.3770796204284,15.2831078773546));
+#6753=CARTESIAN_POINT('Ctrl Pts',(-73.2366389638677,-90.3739379867102,15.2832572113496));
+#6754=CARTESIAN_POINT('Ctrl Pts',(-73.1715481231025,-90.3720079906939,15.2833489515208));
+#6755=CARTESIAN_POINT('Ctrl Pts',(-73.1064731899098,-90.3717631116484,15.2833575762564));
+#6756=CARTESIAN_POINT('Ctrl Pts',(-73.041555934161,-90.3732099457757,15.2832834647795));
+#6757=CARTESIAN_POINT('Ctrl Pts',(-72.946610784729,-90.3753260223234,15.2831750725628));
+#6758=CARTESIAN_POINT('Ctrl Pts',(-72.8520032668926,-90.3810622565872,15.2828896262154));
+#6759=CARTESIAN_POINT('Ctrl Pts',(-72.7580230908704,-90.390360917157,15.2824285180269));
+#6760=CARTESIAN_POINT('Ctrl Pts',(-72.6437609251983,-90.4016663343154,15.2818678974528));
+#6761=CARTESIAN_POINT('Ctrl Pts',(-72.5297733654828,-90.4183024012972,15.2810440769179));
+#6762=CARTESIAN_POINT('Ctrl Pts',(-72.4165348255264,-90.4402964246342,15.2799536553321));
+#6763=CARTESIAN_POINT('Ctrl Pts',(-72.3629940868021,-90.4506955012864,15.2794380890131));
+#6764=CARTESIAN_POINT('Ctrl Pts',(-72.3096208083077,-90.462291611497,15.2788629596089));
+#6765=CARTESIAN_POINT('Ctrl Pts',(-72.256464957606,-90.4750835895666,15.2782281051143));
+#6766=CARTESIAN_POINT('Ctrl Pts',(-72.1434346821961,-90.5022843733967,15.2768781544049));
+#6767=CARTESIAN_POINT('Ctrl Pts',(-72.0313883357804,-90.5348957390247,15.2752579816887));
+#6768=CARTESIAN_POINT('Ctrl Pts',(-71.9212513419907,-90.5722619133821,15.2733755590184));
+#6769=CARTESIAN_POINT('Ctrl Pts',(-71.9059914269962,-90.5774391442538,15.2731147419311));
+#6770=CARTESIAN_POINT('Ctrl Pts',(-71.8907681429373,-90.5827075761395,15.272848894484));
+#6771=CARTESIAN_POINT('Ctrl Pts',(-71.8755839244228,-90.5880653930214,15.2725780418087));
+#6772=CARTESIAN_POINT('Ctrl Pts',(-71.7714305742776,-90.6248163510754,15.2707201777709));
+#6773=CARTESIAN_POINT('Ctrl Pts',(-71.6691173978138,-90.6657763474651,15.2686266428709));
+#6774=CARTESIAN_POINT('Ctrl Pts',(-71.5693735247593,-90.7111582652968,15.2662999369328));
+#6775=CARTESIAN_POINT('Ctrl Pts',(-71.5494502851023,-90.7202230308544,15.2658351913941));
+#6776=CARTESIAN_POINT('Ctrl Pts',(-71.5296294636807,-90.7294640825052,15.2653611496906));
+#6777=CARTESIAN_POINT('Ctrl Pts',(-71.5099167230813,-90.7388829045117,15.2648778419711));
+#6778=CARTESIAN_POINT('Ctrl Pts',(-71.4769626554021,-90.7546284826719,15.2640698896106));
+#6779=CARTESIAN_POINT('Ctrl Pts',(-71.4443106489706,-90.7708708770722,15.263236040855));
+#6780=CARTESIAN_POINT('Ctrl Pts',(-71.4119713324482,-90.787591929271,15.2623766043343));
+#6781=CARTESIAN_POINT('Ctrl Pts',(-71.3301671766323,-90.8298887897668,15.2602026103661));
+#6782=CARTESIAN_POINT('Ctrl Pts',(-71.2498957215775,-90.8754951244061,15.2578508688361));
+#6783=CARTESIAN_POINT('Ctrl Pts',(-71.1714511455853,-90.9241605086429,15.2553236396329));
+#6784=CARTESIAN_POINT('Ctrl Pts',(-71.090710636071,-90.9742502423088,15.252722442916));
+#6785=CARTESIAN_POINT('Ctrl Pts',(-71.0119059621275,-91.0275804173408,15.2499353251717));
+#6786=CARTESIAN_POINT('Ctrl Pts',(-70.9353322672072,-91.0838284190111,15.2469672689401));
+#6787=CARTESIAN_POINT('Ctrl Pts',(-70.8577412500504,-91.1408237052797,15.243959780504));
+#6788=CARTESIAN_POINT('Ctrl Pts',(-70.7824413046247,-91.2008143445637,15.2407665111956));
+#6789=CARTESIAN_POINT('Ctrl Pts',(-70.709706956519,-91.2634209684924,15.2373952865));
+#6790=CARTESIAN_POINT('Ctrl Pts',(-70.6359864447397,-91.3268764400406,15.2339783532855));
+#6791=CARTESIAN_POINT('Ctrl Pts',(-70.5649020099161,-91.3930187168526,15.2303786052076));
+#6792=CARTESIAN_POINT('Ctrl Pts',(-70.4966997460329,-91.4614166783319,15.2266069165275));
+#6793=CARTESIAN_POINT('Ctrl Pts',(-70.4345992826033,-91.5236953310286,15.223172666671));
+#6794=CARTESIAN_POINT('Ctrl Pts',(-70.3748880477196,-91.587843294345,15.2195959018815));
+#6795=CARTESIAN_POINT('Ctrl Pts',(-70.317719398333,-91.6535161914435,15.2158867496328));
+#6796=CARTESIAN_POINT('Ctrl Pts',(-70.2463942139281,-91.7354515099475,15.2112591089423));
+#6797=CARTESIAN_POINT('Ctrl Pts',(-70.1783829702381,-91.8204998973039,15.2063761248227));
+#6798=CARTESIAN_POINT('Ctrl Pts',(-70.1140514322653,-91.9081987556484,15.2012473153634));
+#6799=CARTESIAN_POINT('Ctrl Pts',(-70.0487248481923,-91.9972540934077,15.1960391762004));
+#6800=CARTESIAN_POINT('Ctrl Pts',(-69.987193207365,-92.089041896895,15.1905775463211));
+#6801=CARTESIAN_POINT('Ctrl Pts',(-69.92980143551,-92.1830404981113,15.184874974089));
+#6802=CARTESIAN_POINT('Ctrl Pts',(-69.8724671423821,-92.2769449583077,15.1791781130692));
+#6803=CARTESIAN_POINT('Ctrl Pts',(-69.8192648447205,-92.373055026213,15.1732407983572));
+#6804=CARTESIAN_POINT('Ctrl Pts',(-69.7704937769556,-92.470824383651,15.1670780542778));
+#6805=CARTESIAN_POINT('Ctrl Pts',(-69.7223953285322,-92.567245368707,15.1610003028192));
+#6806=CARTESIAN_POINT('Ctrl Pts',(-69.678606994221,-92.6652794315737,15.1547033089999));
+#6807=CARTESIAN_POINT('Ctrl Pts',(-69.6393674390564,-92.7643884268899,15.1482037864262));
+#6808=CARTESIAN_POINT('Ctrl Pts',(-69.627461321667,-92.7944602084796,15.1462316927465));
+#6809=CARTESIAN_POINT('Ctrl Pts',(-69.6159736296443,-92.8246308964729,15.1442409689072));
+#6810=CARTESIAN_POINT('Ctrl Pts',(-69.6049100770089,-92.8548853569535,15.1422321219558));
+#6811=CARTESIAN_POINT('Ctrl Pts',(-69.5843193033576,-92.9111930158246,15.1384933850203));
+#6812=CARTESIAN_POINT('Ctrl Pts',(-69.5651109879859,-92.9680295185404,15.1346714604666));
+#6813=CARTESIAN_POINT('Ctrl Pts',(-69.5473598643567,-93.0252868383794,15.1307686654223));
+#6814=CARTESIAN_POINT('Ctrl Pts',(-69.5201424741472,-93.113078171985,15.1247845994079));
+#6815=CARTESIAN_POINT('Ctrl Pts',(-69.4963535897196,-93.2018593134707,15.1186102846917));
+#6816=CARTESIAN_POINT('Ctrl Pts',(-69.4760027799041,-93.2912603818744,15.112263193911));
+#6817=CARTESIAN_POINT('Ctrl Pts',(-69.4551235889038,-93.3829826278068,15.1057513095237));
+#6818=CARTESIAN_POINT('Ctrl Pts',(-69.4378633702137,-93.4753568939956,15.0990575705417));
+#6819=CARTESIAN_POINT('Ctrl Pts',(-69.4241786870118,-93.5679722904552,15.0922034395475));
+#6820=CARTESIAN_POINT('Ctrl Pts',(-69.4103187031416,-93.661774089308,15.0852615071971));
+#6821=CARTESIAN_POINT('Ctrl Pts',(-69.4001263339915,-93.7558226222395,15.0781550663223));
+#6822=CARTESIAN_POINT('Ctrl Pts',(-69.393502639424,-93.849688108725,15.0709088127285));
+#6823=CARTESIAN_POINT('Ctrl Pts',(-69.3867896600097,-93.9448188657468,15.0635648824325));
+#6824=CARTESIAN_POINT('Ctrl Pts',(-69.3837420569707,-94.0397609408328,15.0560773669148));
+#6825=CARTESIAN_POINT('Ctrl Pts',(-69.3842039434031,-94.1340737579082,15.0484741076789));
+#6826=CARTESIAN_POINT('Ctrl Pts',(-69.3843875411055,-94.1715626627539,15.0454518475996));
+#6827=CARTESIAN_POINT('Ctrl Pts',(-69.3851250796942,-94.2089522736135,15.0424113212832));
+#6828=CARTESIAN_POINT('Ctrl Pts',(-69.3864045866205,-94.2462155737945,15.0393543567379));
+#6829=CARTESIAN_POINT('Ctrl Pts',(-69.3905580306093,-94.3671770371245,15.0294310567901));
+#6830=CARTESIAN_POINT('Ctrl Pts',(-69.4004627597731,-94.4878707414014,15.019238250684));
+#6831=CARTESIAN_POINT('Ctrl Pts',(-69.4159695450259,-94.6075921455277,15.0088072912905));
+#6832=CARTESIAN_POINT('Ctrl Pts',(-69.4312460156284,-94.7255353865542,14.9985312578038));
+#6833=CARTESIAN_POINT('Ctrl Pts',(-69.4519589461953,-94.8425341475835,14.9880241306395));
+#6834=CARTESIAN_POINT('Ctrl Pts',(-69.4779116186254,-94.9579186961826,14.9773182136169));
+#6835=CARTESIAN_POINT('Ctrl Pts',(-69.5044512015565,-95.0759126255078,14.9663701860703));
+#6836=CARTESIAN_POINT('Ctrl Pts',(-69.5364700648331,-95.1922175357315,14.9552143034764));
+#6837=CARTESIAN_POINT('Ctrl Pts',(-69.5737046227875,-95.3061351437284,14.9438870879118));
+#6838=CARTESIAN_POINT('Ctrl Pts',(-69.6109391807418,-95.4200527517253,14.9325598723472));
+#6839=CARTESIAN_POINT('Ctrl Pts',(-69.653389076463,-95.5315821388258,14.9210613604042));
+#6840=CARTESIAN_POINT('Ctrl Pts',(-69.7007420974264,-95.6400569777889,14.9094295310117));
+#6841=CARTESIAN_POINT('Ctrl Pts',(-69.7345179774808,-95.7174297213899,14.9011328000666));
+#6842=CARTESIAN_POINT('Ctrl Pts',(-69.7709913024992,-95.7937133520741,14.8927471442295));
+#6843=CARTESIAN_POINT('Ctrl Pts',(-69.8100978526774,-95.8685786652309,14.88428181847));
+#6844=CARTESIAN_POINT('Ctrl Pts',(-69.8547391966781,-95.9540397499627,14.8746183856797));
+#6845=CARTESIAN_POINT('Ctrl Pts',(-69.9028128039209,-96.037651260627,14.8648510519941));
+#6846=CARTESIAN_POINT('Ctrl Pts',(-69.9540932227522,-96.1191869462766,14.8550229297375));
+#6847=CARTESIAN_POINT('Ctrl Pts',(-70.0060733721422,-96.2018352010543,14.8450607009811));
+#6848=CARTESIAN_POINT('Ctrl Pts',(-70.0613481334089,-96.2823503395768,14.8350360884713));
+#6849=CARTESIAN_POINT('Ctrl Pts',(-70.1196367037391,-96.3605248053577,14.8249961725681));
+#6850=CARTESIAN_POINT('Ctrl Pts',(-70.179159315238,-96.4403543213238,14.8147436992205));
+#6851=CARTESIAN_POINT('Ctrl Pts',(-70.2418243410103,-96.5177427062681,14.8044753559272));
+#6852=CARTESIAN_POINT('Ctrl Pts',(-70.3072901639951,-96.5925023355675,14.7942422859156));
+#6853=CARTESIAN_POINT('Ctrl Pts',(-70.3206754715171,-96.6077878782031,14.7921500065741));
+#6854=CARTESIAN_POINT('Ctrl Pts',(-70.3341777376589,-96.6229636438144,14.7900592025005));
+#6855=CARTESIAN_POINT('Ctrl Pts',(-70.3477938520432,-96.6380282128303,14.7879703105199));
+#6856=CARTESIAN_POINT('Ctrl Pts',(-70.4080089378276,-96.7046488573108,14.7787325201888));
+#6857=CARTESIAN_POINT('Ctrl Pts',(-70.4704526214073,-96.7690925914395,14.7695322108452));
+#6858=CARTESIAN_POINT('Ctrl Pts',(-70.5350104281953,-96.831167570878,14.7604135120471));
+#6859=CARTESIAN_POINT('Ctrl Pts',(-70.6175283993959,-96.9105119851393,14.7487579654564));
+#6860=CARTESIAN_POINT('Ctrl Pts',(-70.7040825934032,-96.9865477782663,14.737167377064));
+#6861=CARTESIAN_POINT('Ctrl Pts',(-70.7946322230545,-97.0588497284666,14.7257450964668));
+#6862=CARTESIAN_POINT('Ctrl Pts',(-70.8806733357,-97.1275517238875,14.714891537647));
+#6863=CARTESIAN_POINT('Ctrl Pts',(-70.9703217179673,-97.1928822763336,14.7041900539618));
+#6864=CARTESIAN_POINT('Ctrl Pts',(-71.063509228736,-97.2545049712193,14.6937284262279));
+#6865=CARTESIAN_POINT('Ctrl Pts',(-71.1581598592925,-97.3170951925848,14.6831025424213));
+#6866=CARTESIAN_POINT('Ctrl Pts',(-71.2564614469927,-97.3758595717839,14.6727243174705));
+#6867=CARTESIAN_POINT('Ctrl Pts',(-71.3576965972842,-97.4302259413459,14.6628407714952));
+#6868=CARTESIAN_POINT('Ctrl Pts',(-71.3994953373747,-97.4526731421891,14.6587599777372));
+#6869=CARTESIAN_POINT('Ctrl Pts',(-71.4417938169012,-97.4743710689158,14.6547634567081));
+#6870=CARTESIAN_POINT('Ctrl Pts',(-71.4845402390904,-97.4952816934468,14.6508682572564));
+#6871=CARTESIAN_POINT('Ctrl Pts',(-71.5578659282448,-97.5311510335193,14.6441865709408));
+#6872=CARTESIAN_POINT('Ctrl Pts',(-71.6325106113905,-97.5647032948152,14.6378030898082));
+#6873=CARTESIAN_POINT('Ctrl Pts',(-71.708738917124,-97.5959963233223,14.6317286876878));
+#6874=CARTESIAN_POINT('Ctrl Pts',(-71.7242384808031,-97.6023591603734,14.6304935745423));
+#6875=CARTESIAN_POINT('Ctrl Pts',(-71.7398034704898,-97.6086286240171,14.6292712348039));
+#6876=CARTESIAN_POINT('Ctrl Pts',(-71.7554326358306,-97.6148021765311,14.6280627830907));
+#6877=CARTESIAN_POINT('Ctrl Pts',(-71.8166816850947,-97.6389956771959,14.6233269883823));
+#6878=CARTESIAN_POINT('Ctrl Pts',(-71.8791713838288,-97.6618159940986,14.6187688397711));
+#6879=CARTESIAN_POINT('Ctrl Pts',(-71.9428086390876,-97.6830638120003,14.6144680789591));
+#6880=CARTESIAN_POINT('Ctrl Pts',(-72.0274918969251,-97.7113386713501,14.6087449779979));
+#6881=CARTESIAN_POINT('Ctrl Pts',(-72.1142085810248,-97.7368269145361,14.6034781594726));
+#6882=CARTESIAN_POINT('Ctrl Pts',(-72.2024596980281,-97.7592820409437,14.5987712887552));
+#6883=CARTESIAN_POINT('Ctrl Pts',(-72.2903036727381,-97.7816335717031,14.59408613296));
+#6884=CARTESIAN_POINT('Ctrl Pts',(-72.3796671318608,-97.8009794417394,14.589955939949));
+#6885=CARTESIAN_POINT('Ctrl Pts',(-72.4700312835527,-97.8171195378801,14.5864743312097));
+#6886=CARTESIAN_POINT('Ctrl Pts',(-72.558393549187,-97.832902073718,14.5830698524369));
+#6887=CARTESIAN_POINT('Ctrl Pts',(-72.6477118322987,-97.8456190248635,14.5802856502197));
+#6888=CARTESIAN_POINT('Ctrl Pts',(-72.73748777663,-97.8551297435839,14.5781989849941));
+#6889=CARTESIAN_POINT('Ctrl Pts',(-72.7750434978283,-97.8591083361046,14.5773260761315));
+#6890=CARTESIAN_POINT('Ctrl Pts',(-72.812679216934,-97.8625264364209,14.5765750997343));
+#6891=CARTESIAN_POINT('Ctrl Pts',(-72.8503582628642,-97.8653764117555,14.5759510939191));
+#6892=CARTESIAN_POINT('Ctrl Pts',(-72.929932264714,-97.8713952462815,14.5746332622525));
+#6893=CARTESIAN_POINT('Ctrl Pts',(-73.0102113287442,-97.8749176944887,14.5738461316381));
+#6894=CARTESIAN_POINT('Ctrl Pts',(-73.0908862187882,-97.8757948884934,14.573648882627));
+#6895=CARTESIAN_POINT('Ctrl Pts',(-73.1870803917761,-97.876840826725,14.5734136891798));
+#6896=CARTESIAN_POINT('Ctrl Pts',(-73.2838376568,-97.874124154129,14.5740176562605));
+#6897=CARTESIAN_POINT('Ctrl Pts',(-73.3798869055325,-97.8677305253028,14.5754220859333));
+#6898=CARTESIAN_POINT('Ctrl Pts',(-73.4160750109974,-97.8653216223981,14.5759512274913));
+#6899=CARTESIAN_POINT('Ctrl Pts',(-73.4521624791837,-97.8623912825192,14.5765938746686));
+#6900=CARTESIAN_POINT('Ctrl Pts',(-73.4880812607619,-97.8589459280936,14.5773475327906));
+#6901=CARTESIAN_POINT('Ctrl Pts',(-73.5855695606412,-97.8495947827968,14.5793930601103));
+#6902=CARTESIAN_POINT('Ctrl Pts',(-73.6818138053061,-97.8364463012534,14.5822570240495));
+#6903=CARTESIAN_POINT('Ctrl Pts',(-73.77647862767,-97.8197904856657,14.5858218269038));
+#6904=CARTESIAN_POINT('Ctrl Pts',(-73.7986064869462,-97.8158971963292,14.5866550979536));
+#6905=CARTESIAN_POINT('Ctrl Pts',(-73.8206481351863,-97.8118124748732,14.5875266233209));
+#6906=CARTESIAN_POINT('Ctrl Pts',(-73.8425994577207,-97.807540386424,14.5884348365769));
+#6907=CARTESIAN_POINT('Ctrl Pts',(-73.9392017038374,-97.7887400002902,14.5924316545522));
+#6908=CARTESIAN_POINT('Ctrl Pts',(-74.0345462659213,-97.766210909924,14.5971717954496));
+#6909=CARTESIAN_POINT('Ctrl Pts',(-74.1282712977102,-97.7402142792017,14.6025374538741));
+#6910=CARTESIAN_POINT('Ctrl Pts',(-74.22381181755,-97.7137140842603,14.6080070470594));
+#6911=CARTESIAN_POINT('Ctrl Pts',(-74.3176689297045,-97.6836111412258,14.6141263876923));
+#6912=CARTESIAN_POINT('Ctrl Pts',(-74.4094805562197,-97.6502327033212,14.6207612657083));
+#6913=CARTESIAN_POINT('Ctrl Pts',(-74.5033513223883,-97.6161056579943,14.6275449499371));
+#6914=CARTESIAN_POINT('Ctrl Pts',(-74.5950832108149,-97.5785550701163,14.6348672763518));
+#6915=CARTESIAN_POINT('Ctrl Pts',(-74.6843199747325,-97.5379758307998,14.6425790133149));
+#6916=CARTESIAN_POINT('Ctrl Pts',(-74.76181870239,-97.5027343083792,14.6492763628873));
+#6917=CARTESIAN_POINT('Ctrl Pts',(-74.8374358323277,-97.4652094929812,14.6562672053179));
+#6918=CARTESIAN_POINT('Ctrl Pts',(-74.9109614508974,-97.4256816304331,14.6634529173785));
+#6919=CARTESIAN_POINT('Ctrl Pts',(-74.9172151672363,-97.422319590852,14.6640640976146));
+#6920=CARTESIAN_POINT('Ctrl Pts',(-74.9234577192175,-97.4189409456217,14.6646769663933));
+#6921=CARTESIAN_POINT('Ctrl Pts',(-74.9296889331911,-97.4155458153908,14.6652914668912));
+#6922=CARTESIAN_POINT('Ctrl Pts',(-75.0120854375629,-97.3706513752234,14.6734171215682));
+#6923=CARTESIAN_POINT('Ctrl Pts',(-75.0924968262835,-97.3228710663744,14.6818285450943));
+#6924=CARTESIAN_POINT('Ctrl Pts',(-75.1707171091252,-97.2723378132202,14.6904635317575));
+#6925=CARTESIAN_POINT('Ctrl Pts',(-75.2499397744161,-97.2211569831944,14.6992091746184));
+#6926=CARTESIAN_POINT('Ctrl Pts',(-75.3269146757093,-97.1671523260447,14.7081840345891));
+#6927=CARTESIAN_POINT('Ctrl Pts',(-75.4014616558163,-97.1105033118982,14.7173187692225));
+#6928=CARTESIAN_POINT('Ctrl Pts',(-75.4766302098651,-97.0533819573433,14.7265296694229));
+#6929=CARTESIAN_POINT('Ctrl Pts',(-75.5493300808802,-96.9935721610386,14.7359029922145));
+#6930=CARTESIAN_POINT('Ctrl Pts',(-75.6194126030754,-96.9312972175166,14.7453647264616));
+#6931=CARTESIAN_POINT('Ctrl Pts',(-75.6904820504123,-96.8681452977452,14.7549597039642));
+#6932=CARTESIAN_POINT('Ctrl Pts',(-75.758859785056,-96.802458513732,14.7646454596001));
+#6933=CARTESIAN_POINT('Ctrl Pts',(-75.8244295046132,-96.7345069944755,14.7743438758254));
+#6934=CARTESIAN_POINT('Ctrl Pts',(-75.8568578905446,-96.7009006574962,14.7791403578967));
+#6935=CARTESIAN_POINT('Ctrl Pts',(-75.8886000600642,-96.6667409327185,14.7839399357818));
+#6936=CARTESIAN_POINT('Ctrl Pts',(-75.9196455051904,-96.6320635448128,14.7887332412506));
+#6937=CARTESIAN_POINT('Ctrl Pts',(-75.9541757704363,-96.5934936548483,14.7940645904571));
+#6938=CARTESIAN_POINT('Ctrl Pts',(-75.9879519790518,-96.5541632024658,14.7994122331284));
+#6939=CARTESIAN_POINT('Ctrl Pts',(-76.0209623514754,-96.5140923737305,14.8047656690313));
+#6940=CARTESIAN_POINT('Ctrl Pts',(-76.1078384152121,-96.408634736764,14.8188547387558));
+#6941=CARTESIAN_POINT('Ctrl Pts',(-76.1894081173038,-96.29804581712,14.8329840883948));
+#6942=CARTESIAN_POINT('Ctrl Pts',(-76.2649746491587,-96.1830490432806,14.8470476935094));
+#6943=CARTESIAN_POINT('Ctrl Pts',(-76.3407658649678,-96.0677103465129,14.8611531143105));
+#6944=CARTESIAN_POINT('Ctrl Pts',(-76.4105175123832,-95.9479382561964,14.875192295071));
+#6945=CARTESIAN_POINT('Ctrl Pts',(-76.4735616888911,-95.8245014574457,14.8890564535487));
+#6946=CARTESIAN_POINT('Ctrl Pts',(-76.5355172928886,-95.7031960198031,14.9026812220838));
+#6947=CARTESIAN_POINT('Ctrl Pts',(-76.5909945531395,-95.5783521113868,14.9161368552698));
+#6948=CARTESIAN_POINT('Ctrl Pts',(-76.6394018169151,-95.4507254712836,14.9293199231613));
+#6949=CARTESIAN_POINT('Ctrl Pts',(-76.6613423620823,-95.39287882094,14.9352951358454));
+#6950=CARTESIAN_POINT('Ctrl Pts',(-76.6818311115106,-95.3344607909741,14.9412143611222));
+#6951=CARTESIAN_POINT('Ctrl Pts',(-76.7008163416603,-95.2755429263383,14.9470680441145));
+#6952=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.4295662194267,3.));
+#6953=CARTESIAN_POINT('',(-76.1315457706143,-94.4295662194267,3.));
+#6954=CARTESIAN_POINT('',(-76.1315457706143,-94.4295662194267,3.));
+#6955=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.4295662194267,3.));
+#6956=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.1254091990418,13.));
+#6957=CARTESIAN_POINT('',(-76.8815457706143,-94.1254091990418,20.));
+#6958=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.1254091990418,20.));
+#6959=CARTESIAN_POINT('',(-76.8815457706143,-94.1254091990418,13.));
+#6960=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,12.0795759736429));
+#6961=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,12.0795759736429));
+#6962=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,3.));
+#6963=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,3.));
+#6964=CARTESIAN_POINT('Origin',(-120.237629588674,-105.829566219427,20.));
+#6965=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.1254091990418,20.));
+#6966=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,20.));
+#6967=CARTESIAN_POINT('Origin',(-70.8321482282874,-77.5251222106383,15.));
+#6968=CARTESIAN_POINT('',(-73.5821482282874,-77.5251222106383,3.));
+#6969=CARTESIAN_POINT('',(-73.5821482282874,-77.5251222106383,15.));
+#6970=CARTESIAN_POINT('Origin',(-70.8321482282874,-77.5251222106383,3.));
+#6971=CARTESIAN_POINT('Origin',(-70.8321482282874,-77.5251222106383,3.));
+#6972=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,15.));
+#6973=CARTESIAN_POINT('',(-201.077709627218,-122.810290591316,3.));
+#6974=CARTESIAN_POINT('',(-201.077709627218,-122.810290591316,15.));
+#6975=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,3.));
+#6976=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,3.));
+#6977=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,15.));
+#6978=CARTESIAN_POINT('',(-72.7853819140103,-122.810290591316,3.));
+#6979=CARTESIAN_POINT('',(-72.7853819140103,-122.810290591316,15.));
+#6980=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,3.));
+#6981=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,3.));
+#6982=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,15.));
+#6983=CARTESIAN_POINT('',(-200.280943312941,-77.5251222106383,3.));
+#6984=CARTESIAN_POINT('',(-200.280943312941,-77.5251222106383,15.));
+#6985=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,3.));
+#6986=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,3.));
+#6987=CARTESIAN_POINT('Origin',(-128.681545770614,-126.482328591575,3.));
+#6988=CARTESIAN_POINT('',(-128.681545770614,-133.482328591575,3.));
+#6989=CARTESIAN_POINT('',(-128.681545770614,-133.482328591575,3.));
+#6990=CARTESIAN_POINT('',(-128.681545770614,-126.482328591575,3.));
+#6991=CARTESIAN_POINT('',(-128.681545770614,-116.396748721995,3.));
+#6992=CARTESIAN_POINT('',(-128.681545770614,-126.482328591575,3.));
+#6993=CARTESIAN_POINT('Origin',(-139.681545770614,-126.482328591575,3.));
+#6994=CARTESIAN_POINT('',(-139.681545770614,-126.482328591575,3.));
+#6995=CARTESIAN_POINT('',(-136.931545770614,-126.482328591575,3.));
+#6996=CARTESIAN_POINT('',(-139.681545770614,-126.482328591575,3.));
+#6997=CARTESIAN_POINT('Origin',(-139.681545770614,-133.482328591575,3.));
+#6998=CARTESIAN_POINT('',(-139.681545770614,-133.482328591575,3.));
+#6999=CARTESIAN_POINT('',(-139.681545770614,-119.896748721995,3.));
+#7000=CARTESIAN_POINT('',(-139.681545770614,-133.482328591575,3.));
+#7001=CARTESIAN_POINT('Origin',(-128.681545770614,-133.482328591575,3.));
+#7002=CARTESIAN_POINT('',(-131.431545770614,-133.482328591575,3.));
+#7003=CARTESIAN_POINT('Origin',(-153.681545770614,-131.687409348463,3.));
+#7004=CARTESIAN_POINT('',(-164.681545770614,-131.687409348463,3.));
+#7005=CARTESIAN_POINT('',(-164.681545770614,-131.687409348463,3.));
+#7006=CARTESIAN_POINT('',(-153.681545770614,-131.687409348463,3.));
+#7007=CARTESIAN_POINT('',(-143.931545770614,-131.687409348463,3.));
+#7008=CARTESIAN_POINT('',(-153.681545770614,-131.687409348463,3.));
+#7009=CARTESIAN_POINT('Origin',(-153.681545770614,-124.687409348463,3.));
+#7010=CARTESIAN_POINT('',(-153.681545770614,-124.687409348463,3.));
+#7011=CARTESIAN_POINT('',(-153.681545770614,-115.499289100439,3.));
+#7012=CARTESIAN_POINT('',(-153.681545770614,-124.687409348463,3.));
+#7013=CARTESIAN_POINT('Origin',(-164.681545770614,-124.687409348463,3.));
+#7014=CARTESIAN_POINT('',(-164.681545770614,-124.687409348463,3.));
+#7015=CARTESIAN_POINT('',(-149.431545770614,-124.687409348463,3.));
+#7016=CARTESIAN_POINT('',(-164.681545770614,-124.687409348463,3.));
+#7017=CARTESIAN_POINT('Origin',(-164.681545770614,-131.687409348463,3.));
+#7018=CARTESIAN_POINT('',(-164.681545770614,-118.999289100439,3.));
+#7019=CARTESIAN_POINT('Origin',(-114.681545770614,-131.687409348463,3.));
+#7020=CARTESIAN_POINT('',(-114.681545770614,-124.687409348463,3.));
+#7021=CARTESIAN_POINT('',(-114.681545770614,-124.687409348463,3.));
+#7022=CARTESIAN_POINT('',(-114.681545770614,-131.687409348463,3.));
+#7023=CARTESIAN_POINT('',(-114.681545770614,-118.999289100439,3.));
+#7024=CARTESIAN_POINT('',(-114.681545770614,-131.687409348463,3.));
+#7025=CARTESIAN_POINT('Origin',(-103.681545770614,-131.687409348463,3.));
+#7026=CARTESIAN_POINT('',(-103.681545770614,-131.687409348463,3.));
+#7027=CARTESIAN_POINT('',(-118.931545770614,-131.687409348463,3.));
+#7028=CARTESIAN_POINT('',(-103.681545770614,-131.687409348463,3.));
+#7029=CARTESIAN_POINT('Origin',(-103.681545770614,-124.687409348463,3.));
+#7030=CARTESIAN_POINT('',(-103.681545770614,-124.687409348463,3.));
+#7031=CARTESIAN_POINT('',(-103.681545770614,-115.499289100439,3.));
+#7032=CARTESIAN_POINT('',(-103.681545770614,-124.687409348463,3.));
+#7033=CARTESIAN_POINT('Origin',(-114.681545770614,-124.687409348463,3.));
+#7034=CARTESIAN_POINT('',(-124.431545770614,-124.687409348463,3.));
+#7035=CARTESIAN_POINT('Origin',(-189.681545770614,-126.18742690406,3.));
+#7036=CARTESIAN_POINT('',(-189.681545770614,-119.18742690406,3.));
+#7037=CARTESIAN_POINT('',(-189.681545770614,-119.18742690406,3.));
+#7038=CARTESIAN_POINT('',(-189.681545770614,-126.18742690406,3.));
+#7039=CARTESIAN_POINT('',(-189.681545770614,-116.249297878237,3.));
+#7040=CARTESIAN_POINT('',(-189.681545770614,-126.18742690406,3.));
+#7041=CARTESIAN_POINT('Origin',(-178.681545770614,-126.18742690406,3.));
+#7042=CARTESIAN_POINT('',(-178.681545770614,-126.18742690406,3.));
+#7043=CARTESIAN_POINT('',(-156.431545770614,-126.18742690406,3.));
+#7044=CARTESIAN_POINT('',(-178.681545770614,-126.18742690406,3.));
+#7045=CARTESIAN_POINT('Origin',(-178.681545770614,-119.18742690406,3.));
+#7046=CARTESIAN_POINT('',(-178.681545770614,-119.18742690406,3.));
+#7047=CARTESIAN_POINT('',(-178.681545770614,-112.749297878237,3.));
+#7048=CARTESIAN_POINT('',(-178.681545770614,-119.18742690406,3.));
+#7049=CARTESIAN_POINT('Origin',(-189.681545770614,-119.18742690406,3.));
+#7050=CARTESIAN_POINT('',(-161.931545770614,-119.18742690406,3.));
+#7051=CARTESIAN_POINT('Origin',(-78.6815457706143,-119.18742690406,3.));
+#7052=CARTESIAN_POINT('',(-78.6815457706143,-126.18742690406,3.));
+#7053=CARTESIAN_POINT('',(-78.6815457706143,-126.18742690406,3.));
+#7054=CARTESIAN_POINT('',(-78.6815457706143,-119.18742690406,3.));
+#7055=CARTESIAN_POINT('',(-78.6815457706143,-112.749297878237,3.));
+#7056=CARTESIAN_POINT('',(-78.6815457706143,-119.18742690406,3.));
+#7057=CARTESIAN_POINT('Origin',(-89.6815457706142,-119.18742690406,3.));
+#7058=CARTESIAN_POINT('',(-89.6815457706142,-119.18742690406,3.));
+#7059=CARTESIAN_POINT('',(-111.931545770614,-119.18742690406,3.));
+#7060=CARTESIAN_POINT('',(-89.6815457706142,-119.18742690406,3.));
+#7061=CARTESIAN_POINT('Origin',(-89.6815457706142,-126.18742690406,3.));
+#7062=CARTESIAN_POINT('',(-89.6815457706142,-126.18742690406,3.));
+#7063=CARTESIAN_POINT('',(-89.6815457706142,-116.249297878237,3.));
+#7064=CARTESIAN_POINT('',(-89.6815457706142,-126.18742690406,3.));
+#7065=CARTESIAN_POINT('Origin',(-78.6815457706143,-126.18742690406,3.));
+#7066=CARTESIAN_POINT('',(-106.431545770614,-126.18742690406,3.));
+#7067=CARTESIAN_POINT('Origin',(-129.181545770614,-102.982328591576,3.));
+#7068=CARTESIAN_POINT('',(-129.181545770614,-102.982328591576,3.));
+#7069=CARTESIAN_POINT('',(-129.181545770614,-104.982328591576,3.));
+#7070=CARTESIAN_POINT('',(-129.181545770614,-104.646748721995,3.));
+#7071=CARTESIAN_POINT('',(-129.181545770614,-102.982328591576,1.));
+#7072=CARTESIAN_POINT('',(-129.181545770614,-102.982328591576,3.));
+#7073=CARTESIAN_POINT('',(-129.181545770614,-104.982328591576,1.));
+#7074=CARTESIAN_POINT('',(-129.181545770614,-104.982328591576,1.));
+#7075=CARTESIAN_POINT('',(-129.181545770614,-104.982328591576,3.));
+#7076=CARTESIAN_POINT('Origin',(-139.181545770614,-102.982328591576,3.));
+#7077=CARTESIAN_POINT('',(-139.181545770614,-102.982328591576,3.));
+#7078=CARTESIAN_POINT('',(-136.681545770614,-102.982328591576,3.));
+#7079=CARTESIAN_POINT('',(-139.181545770614,-102.982328591576,1.));
+#7080=CARTESIAN_POINT('',(-139.181545770614,-102.982328591576,3.));
+#7081=CARTESIAN_POINT('',(-129.181545770614,-102.982328591576,1.));
+#7082=CARTESIAN_POINT('Origin',(-139.181545770614,-104.982328591576,3.));
+#7083=CARTESIAN_POINT('',(-139.181545770614,-104.982328591576,3.));
+#7084=CARTESIAN_POINT('',(-139.181545770614,-105.646748721995,3.));
+#7085=CARTESIAN_POINT('',(-139.181545770614,-104.982328591576,1.));
+#7086=CARTESIAN_POINT('',(-139.181545770614,-104.982328591576,3.));
+#7087=CARTESIAN_POINT('',(-139.181545770614,-102.982328591576,1.));
+#7088=CARTESIAN_POINT('Origin',(-129.181545770614,-104.982328591576,3.));
+#7089=CARTESIAN_POINT('',(-131.681545770614,-104.982328591576,3.));
+#7090=CARTESIAN_POINT('',(-139.181545770614,-104.982328591576,1.));
+#7091=CARTESIAN_POINT('Origin',(-134.181545770614,-103.982328591576,1.));
+#7092=CARTESIAN_POINT('Origin',(-164.181545770614,-101.187409348464,3.));
+#7093=CARTESIAN_POINT('',(-164.181545770614,-101.187409348464,3.));
+#7094=CARTESIAN_POINT('',(-154.181545770614,-101.187409348464,3.));
+#7095=CARTESIAN_POINT('',(-149.181545770614,-101.187409348464,3.));
+#7096=CARTESIAN_POINT('',(-164.181545770614,-101.187409348464,1.));
+#7097=CARTESIAN_POINT('',(-164.181545770614,-101.187409348464,3.));
+#7098=CARTESIAN_POINT('',(-154.181545770614,-101.187409348464,1.));
+#7099=CARTESIAN_POINT('',(-154.181545770614,-101.187409348464,1.));
+#7100=CARTESIAN_POINT('',(-154.181545770614,-101.187409348464,3.));
+#7101=CARTESIAN_POINT('Origin',(-164.181545770614,-103.187409348464,3.));
+#7102=CARTESIAN_POINT('',(-164.181545770614,-103.187409348464,3.));
+#7103=CARTESIAN_POINT('',(-164.181545770614,-104.749289100439,3.));
+#7104=CARTESIAN_POINT('',(-164.181545770614,-103.187409348464,1.));
+#7105=CARTESIAN_POINT('',(-164.181545770614,-103.187409348464,3.));
+#7106=CARTESIAN_POINT('',(-164.181545770614,-101.187409348464,1.));
+#7107=CARTESIAN_POINT('Origin',(-154.181545770614,-103.187409348464,3.));
+#7108=CARTESIAN_POINT('',(-154.181545770614,-103.187409348464,3.));
+#7109=CARTESIAN_POINT('',(-144.181545770614,-103.187409348464,3.));
+#7110=CARTESIAN_POINT('',(-154.181545770614,-103.187409348464,1.));
+#7111=CARTESIAN_POINT('',(-154.181545770614,-103.187409348464,3.));
+#7112=CARTESIAN_POINT('',(-164.181545770614,-103.187409348464,1.));
+#7113=CARTESIAN_POINT('Origin',(-154.181545770614,-101.187409348464,3.));
+#7114=CARTESIAN_POINT('',(-154.181545770614,-103.749289100439,3.));
+#7115=CARTESIAN_POINT('',(-154.181545770614,-103.187409348464,1.));
+#7116=CARTESIAN_POINT('Origin',(-159.181545770614,-102.187409348464,1.));
+#7117=CARTESIAN_POINT('Origin',(-114.181545770614,-103.187409348464,3.));
+#7118=CARTESIAN_POINT('',(-114.181545770614,-103.187409348464,3.));
+#7119=CARTESIAN_POINT('',(-114.181545770614,-101.187409348464,3.));
+#7120=CARTESIAN_POINT('',(-114.181545770614,-104.749289100439,3.));
+#7121=CARTESIAN_POINT('',(-114.181545770614,-103.187409348464,1.));
+#7122=CARTESIAN_POINT('',(-114.181545770614,-103.187409348464,3.));
+#7123=CARTESIAN_POINT('',(-114.181545770614,-101.187409348464,1.));
+#7124=CARTESIAN_POINT('',(-114.181545770614,-101.187409348464,1.));
+#7125=CARTESIAN_POINT('',(-114.181545770614,-101.187409348464,3.));
+#7126=CARTESIAN_POINT('Origin',(-104.181545770614,-103.187409348464,3.));
+#7127=CARTESIAN_POINT('',(-104.181545770614,-103.187409348464,3.));
+#7128=CARTESIAN_POINT('',(-119.181545770614,-103.187409348464,3.));
+#7129=CARTESIAN_POINT('',(-104.181545770614,-103.187409348464,1.));
+#7130=CARTESIAN_POINT('',(-104.181545770614,-103.187409348464,3.));
+#7131=CARTESIAN_POINT('',(-114.181545770614,-103.187409348464,1.));
+#7132=CARTESIAN_POINT('Origin',(-104.181545770614,-101.187409348464,3.));
+#7133=CARTESIAN_POINT('',(-104.181545770614,-101.187409348464,3.));
+#7134=CARTESIAN_POINT('',(-104.181545770614,-103.749289100439,3.));
+#7135=CARTESIAN_POINT('',(-104.181545770614,-101.187409348464,1.));
+#7136=CARTESIAN_POINT('',(-104.181545770614,-101.187409348464,3.));
+#7137=CARTESIAN_POINT('',(-104.181545770614,-103.187409348464,1.));
+#7138=CARTESIAN_POINT('Origin',(-114.181545770614,-101.187409348464,3.));
+#7139=CARTESIAN_POINT('',(-124.181545770614,-101.187409348464,3.));
+#7140=CARTESIAN_POINT('',(-104.181545770614,-101.187409348464,1.));
+#7141=CARTESIAN_POINT('Origin',(-109.181545770614,-102.187409348464,1.));
+#7142=CARTESIAN_POINT('Origin',(-189.181545770614,-97.6874269040599,3.));
+#7143=CARTESIAN_POINT('',(-189.181545770614,-97.6874269040599,3.));
+#7144=CARTESIAN_POINT('',(-189.181545770614,-95.6874269040599,3.));
+#7145=CARTESIAN_POINT('',(-189.181545770614,-101.999297878237,3.));
+#7146=CARTESIAN_POINT('',(-189.181545770614,-97.6874269040599,1.));
+#7147=CARTESIAN_POINT('',(-189.181545770614,-97.6874269040599,3.));
+#7148=CARTESIAN_POINT('',(-189.181545770614,-95.6874269040599,1.));
+#7149=CARTESIAN_POINT('',(-189.181545770614,-95.6874269040599,1.));
+#7150=CARTESIAN_POINT('',(-189.181545770614,-95.6874269040599,3.));
+#7151=CARTESIAN_POINT('Origin',(-179.181545770614,-97.6874269040604,3.));
+#7152=CARTESIAN_POINT('',(-179.181545770614,-97.6874269040599,3.));
+#7153=CARTESIAN_POINT('',(-156.681545770614,-97.6874269040614,3.));
+#7154=CARTESIAN_POINT('',(-179.181545770614,-97.6874269040599,1.));
+#7155=CARTESIAN_POINT('',(-179.181545770614,-97.6874269040599,3.));
+#7156=CARTESIAN_POINT('',(-189.181545770614,-97.6874269040599,1.));
+#7157=CARTESIAN_POINT('Origin',(-179.181545770614,-95.6874269040599,3.));
+#7158=CARTESIAN_POINT('',(-179.181545770614,-95.6874269040599,3.));
+#7159=CARTESIAN_POINT('',(-179.181545770614,-100.999297878237,3.));
+#7160=CARTESIAN_POINT('',(-179.181545770614,-95.6874269040599,1.));
+#7161=CARTESIAN_POINT('',(-179.181545770614,-95.6874269040599,3.));
+#7162=CARTESIAN_POINT('',(-179.181545770614,-97.6874269040599,1.));
+#7163=CARTESIAN_POINT('Origin',(-189.181545770614,-95.6874269040599,3.));
+#7164=CARTESIAN_POINT('',(-161.681545770614,-95.6874269040599,3.));
+#7165=CARTESIAN_POINT('',(-179.181545770614,-95.6874269040599,1.));
+#7166=CARTESIAN_POINT('Origin',(-184.181545770614,-96.68742690406,1.));
+#7167=CARTESIAN_POINT('Origin',(-89.1815457706143,-97.68742690406,3.));
+#7168=CARTESIAN_POINT('',(-89.1815457706143,-97.68742690406,3.));
+#7169=CARTESIAN_POINT('',(-89.1815457706143,-95.68742690406,3.));
+#7170=CARTESIAN_POINT('',(-89.1815457706143,-101.999297878237,3.));
+#7171=CARTESIAN_POINT('',(-89.1815457706143,-97.68742690406,1.));
+#7172=CARTESIAN_POINT('',(-89.1815457706143,-97.68742690406,3.));
+#7173=CARTESIAN_POINT('',(-89.1815457706143,-95.68742690406,1.));
+#7174=CARTESIAN_POINT('',(-89.1815457706143,-95.68742690406,1.));
+#7175=CARTESIAN_POINT('',(-89.1815457706143,-95.68742690406,3.));
+#7176=CARTESIAN_POINT('Origin',(-79.1815457706143,-97.68742690406,3.));
+#7177=CARTESIAN_POINT('',(-79.1815457706143,-97.68742690406,3.));
+#7178=CARTESIAN_POINT('',(-106.681545770614,-97.68742690406,3.));
+#7179=CARTESIAN_POINT('',(-79.1815457706143,-97.68742690406,1.));
+#7180=CARTESIAN_POINT('',(-79.1815457706143,-97.68742690406,3.));
+#7181=CARTESIAN_POINT('',(-89.1815457706143,-97.68742690406,1.));
+#7182=CARTESIAN_POINT('Origin',(-79.1815457706143,-95.68742690406,3.));
+#7183=CARTESIAN_POINT('',(-79.1815457706143,-95.68742690406,3.));
+#7184=CARTESIAN_POINT('',(-79.1815457706142,-100.999297878237,3.));
+#7185=CARTESIAN_POINT('',(-79.1815457706143,-95.68742690406,1.));
+#7186=CARTESIAN_POINT('',(-79.1815457706143,-95.68742690406,3.));
+#7187=CARTESIAN_POINT('',(-79.1815457706143,-97.68742690406,1.));
+#7188=CARTESIAN_POINT('Origin',(-89.1815457706143,-95.68742690406,3.));
+#7189=CARTESIAN_POINT('',(-111.681545770614,-95.68742690406,3.));
+#7190=CARTESIAN_POINT('',(-79.1815457706143,-95.68742690406,1.));
+#7191=CARTESIAN_POINT('Origin',(-84.1815457706143,-96.68742690406,1.));
+#7192=CARTESIAN_POINT('Origin',(-134.181545770614,-108.982328591576,3.));
+#7193=CARTESIAN_POINT('',(-135.631545770614,-108.982328591576,6.));
+#7194=CARTESIAN_POINT('Origin',(-134.181545770614,-108.982328591576,6.));
+#7195=CARTESIAN_POINT('',(-135.631545770614,-108.982328591576,3.));
+#7196=CARTESIAN_POINT('',(-135.631545770614,-108.982328591576,3.));
+#7197=CARTESIAN_POINT('Origin',(-134.181545770614,-108.982328591576,3.));
+#7198=CARTESIAN_POINT('Origin',(-134.181545770614,-108.982328591576,6.));
+#7199=CARTESIAN_POINT('Origin',(-159.181545770614,-107.187409348464,3.));
+#7200=CARTESIAN_POINT('',(-160.631545770614,-107.187409348464,6.));
+#7201=CARTESIAN_POINT('Origin',(-159.181545770614,-107.187409348464,6.));
+#7202=CARTESIAN_POINT('',(-160.631545770614,-107.187409348464,3.));
+#7203=CARTESIAN_POINT('',(-160.631545770614,-107.187409348464,3.));
+#7204=CARTESIAN_POINT('Origin',(-159.181545770614,-107.187409348464,3.));
+#7205=CARTESIAN_POINT('Origin',(-159.181545770614,-107.187409348464,6.));
+#7206=CARTESIAN_POINT('Origin',(-109.181545770614,-107.187409348464,3.));
+#7207=CARTESIAN_POINT('',(-110.631545770614,-107.187409348464,6.));
+#7208=CARTESIAN_POINT('Origin',(-109.181545770614,-107.187409348464,6.));
+#7209=CARTESIAN_POINT('',(-110.631545770614,-107.187409348464,3.));
+#7210=CARTESIAN_POINT('',(-110.631545770614,-107.187409348464,3.));
+#7211=CARTESIAN_POINT('Origin',(-109.181545770614,-107.187409348464,3.));
+#7212=CARTESIAN_POINT('Origin',(-109.181545770614,-107.187409348464,6.));
+#7213=CARTESIAN_POINT('Origin',(-184.181545770614,-101.68742690406,3.));
+#7214=CARTESIAN_POINT('',(-185.631545770614,-101.68742690406,6.));
+#7215=CARTESIAN_POINT('Origin',(-184.181545770614,-101.68742690406,6.));
+#7216=CARTESIAN_POINT('',(-185.631545770614,-101.68742690406,3.));
+#7217=CARTESIAN_POINT('',(-185.631545770614,-101.68742690406,3.));
+#7218=CARTESIAN_POINT('Origin',(-184.181545770614,-101.68742690406,3.));
+#7219=CARTESIAN_POINT('Origin',(-184.181545770614,-101.68742690406,6.));
+#7220=CARTESIAN_POINT('Origin',(-84.1815457706143,-101.68742690406,3.));
+#7221=CARTESIAN_POINT('',(-85.6315457706143,-101.68742690406,6.));
+#7222=CARTESIAN_POINT('Origin',(-84.1815457706143,-101.68742690406,6.));
+#7223=CARTESIAN_POINT('',(-85.6315457706143,-101.68742690406,3.));
+#7224=CARTESIAN_POINT('',(-85.6315457706143,-101.68742690406,3.));
+#7225=CARTESIAN_POINT('Origin',(-84.1815457706143,-101.68742690406,3.));
+#7226=CARTESIAN_POINT('Origin',(-84.1815457706143,-101.68742690406,6.));
+#7227=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,3.));
+#7228=CARTESIAN_POINT('',(-201.181545770614,-118.704731035464,3.));
+#7229=CARTESIAN_POINT('',(-201.181545770614,-118.704731035464,3.));
+#7230=CARTESIAN_POINT('',(-195.571953037155,-126.982317151194,3.));
+#7231=CARTESIAN_POINT('',(-195.571953037155,-126.982317151194,3.));
+#7232=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,3.));
+#7233=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,3.));
+#7234=CARTESIAN_POINT('Origin',(-70.8321482282875,-77.5251222106383,3.));
+#7235=CARTESIAN_POINT('',(-74.6770218864968,-74.3287263414744,3.));
+#7236=CARTESIAN_POINT('',(-74.6770218864968,-74.3287263414744,3.));
+#7237=CARTESIAN_POINT('',(-67.1907887229121,-80.9515636522234,3.));
+#7238=CARTESIAN_POINT('Origin',(-70.8321482282875,-77.5251222106383,3.));
+#7239=CARTESIAN_POINT('',(-67.1907887229121,-80.9515636522234,3.));
+#7240=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,3.));
+#7241=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,3.));
+#7242=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,3.));
+#7243=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,3.));
+#7244=CARTESIAN_POINT('',(-201.172302818316,-80.9515636522235,3.));
+#7245=CARTESIAN_POINT('',(-201.172302818316,-80.9515636522235,3.));
+#7246=CARTESIAN_POINT('',(-193.686069654732,-74.3287263414743,3.));
+#7247=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,3.));
+#7248=CARTESIAN_POINT('',(-193.686069654732,-74.3287263414743,3.));
+#7249=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,3.));
+#7250=CARTESIAN_POINT('',(-65.8550730591838,-125.553467194865,3.));
+#7251=CARTESIAN_POINT('',(-65.8550730591838,-125.553467194865,3.));
+#7252=CARTESIAN_POINT('',(-65.9243175321664,-125.656191089986,3.));
+#7253=CARTESIAN_POINT('',(-65.9243175321664,-125.656191089986,3.));
+#7254=CARTESIAN_POINT('Origin',(-74.1815457706141,-120.015430341809,3.));
+#7255=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,3.));
+#7256=CARTESIAN_POINT('',(-67.1815457706141,-118.704731035464,3.));
+#7257=CARTESIAN_POINT('',(-67.1815457706141,-118.704731035464,3.));
+#7258=CARTESIAN_POINT('',(-72.7911385040727,-126.982317151194,3.));
+#7259=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,3.));
+#7260=CARTESIAN_POINT('',(-72.7911385040727,-126.982317151194,3.));
+#7261=CARTESIAN_POINT('Origin',(-201.181545770614,-81.3111688524149,0.));
+#7262=CARTESIAN_POINT('',(-201.181545770614,-81.3111688524149,3.));
+#7263=CARTESIAN_POINT('',(-201.181545770614,-93.8111688524148,3.));
+#7264=CARTESIAN_POINT('',(-201.181545770614,-81.3111688524149,0.));
+#7265=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,0.));
+#7266=CARTESIAN_POINT('',(-67.1815457706142,-81.3111688524149,3.));
+#7267=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,3.));
+#7268=CARTESIAN_POINT('',(-67.1815457706142,-81.3111688524149,0.));
+#7269=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,0.));
+#7270=CARTESIAN_POINT('',(-76.4518160408844,-74.6895472307933,3.));
+#7271=CARTESIAN_POINT('',(-76.4518160408844,-74.6895472307933,0.));
+#7272=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,3.));
+#7273=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,0.));
+#7274=CARTESIAN_POINT('',(-77.4247890138573,-71.8517093929555,0.));
+#7275=CARTESIAN_POINT('',(-64.1815457706142,-81.3111688524149,0.));
+#7276=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,0.));
+#7277=CARTESIAN_POINT('',(-191.911275500344,-74.6895472307933,3.));
+#7278=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,3.));
+#7279=CARTESIAN_POINT('',(-191.911275500344,-74.6895472307933,0.));
+#7280=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,0.));
+#7281=CARTESIAN_POINT('Origin',(-194.181545770614,-81.3111688524149,3.));
+#7282=CARTESIAN_POINT('Origin',(-134.181545770614,-106.311168852415,3.));
+#7283=CARTESIAN_POINT('',(-158.181545770614,-136.628519700765,3.));
+#7284=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,3.));
+#7285=CARTESIAN_POINT('',(-158.181545770614,-141.311168852415,3.));
+#7286=CARTESIAN_POINT('',(-158.181545770614,-122.763467838619,3.));
+#7287=CARTESIAN_POINT('',(-110.181545770614,-141.311168852415,3.));
+#7288=CARTESIAN_POINT('',(-147.681545770614,-141.311168852415,3.));
+#7289=CARTESIAN_POINT('',(-110.181545770614,-136.628519700765,3.));
+#7290=CARTESIAN_POINT('',(-110.181545770614,-125.311168852415,3.));
+#7291=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,3.));
+#7292=CARTESIAN_POINT('',(-67.1815457706141,-113.163299597112,3.));
+#7293=CARTESIAN_POINT('Origin',(-134.181545770614,93.6888311475868,3.));
+#7294=CARTESIAN_POINT('Origin',(-67.1815457706141,-120.015430341809,0.));
+#7295=CARTESIAN_POINT('Origin',(-134.181545770614,-106.311168852415,15.));
+#7296=CARTESIAN_POINT('',(-147.681545770614,-141.311168852415,15.));
+#7297=CARTESIAN_POINT('Origin',(-74.1815457706141,-120.015430341809,0.));
+#7298=CARTESIAN_POINT('',(-64.1815457706141,-120.015430341809,0.));
+#7299=CARTESIAN_POINT('',(-70.5451821342505,-129.330840129045,0.));
+#7300=CARTESIAN_POINT('Origin',(-134.181545770614,93.6888311475868,0.));
+#7301=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,0.));
+#7302=CARTESIAN_POINT('',(-110.181545770614,-136.628519700765,0.));
+#7303=CARTESIAN_POINT('Origin',(-110.181545770614,-144.311168852415,0.));
+#7304=CARTESIAN_POINT('',(-110.181545770614,-141.311168852415,0.));
+#7305=CARTESIAN_POINT('Origin',(-161.181545770614,-141.311168852415,0.));
+#7306=CARTESIAN_POINT('',(-158.181545770614,-141.311168852415,0.));
+#7307=CARTESIAN_POINT('Origin',(-158.181545770614,-139.215766824823,0.));
+#7308=CARTESIAN_POINT('',(-158.181545770614,-136.628519700765,0.));
+#7309=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,0.));
+#7310=CARTESIAN_POINT('Origin',(-204.181545770614,-81.3111688524149,0.));
+#7311=CARTESIAN_POINT('Origin',(-134.181545770614,93.6888311475868,0.));
+#7312=CARTESIAN_POINT('Origin',(-64.1815457706141,-120.015430341809,0.));
+#7313=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,0.));
+#7314=CARTESIAN_POINT('Origin',(-107.181545770614,-144.311168852415,0.));
+#7315=CARTESIAN_POINT('Origin',(-161.181545770614,-139.215766824823,0.));
+#7316=CARTESIAN_POINT('Origin',(-134.181545770614,33.6888311475855,3.));
+#7317=CARTESIAN_POINT('',(-197.817909406978,-129.330840129045,3.));
+#7318=CARTESIAN_POINT('',(-70.5451821342506,-129.330840129045,3.));
+#7319=CARTESIAN_POINT('Origin',(-134.181545770614,93.6888311475868,3.));
+#7320=CARTESIAN_POINT('',(-190.938302527371,-71.8517093929555,3.));
+#7321=CARTESIAN_POINT('',(-77.4247890138574,-71.8517093929555,3.));
+#7322=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,3.));
+#7323=CARTESIAN_POINT('Origin',(-74.1815457706141,-120.015430341809,3.));
+#7324=CARTESIAN_POINT('',(-70.5451821342505,-129.330840129045,3.));
+#7325=CARTESIAN_POINT('',(-64.1815457706141,-120.015430341809,3.));
+#7326=CARTESIAN_POINT('Origin',(-70.8321482282875,-77.5251222106383,3.));
+#7327=CARTESIAN_POINT('Origin',(-74.1815457706141,-81.3111688524149,3.));
+#7328=CARTESIAN_POINT('',(-64.1815457706141,-81.3111688524149,3.));
+#7329=CARTESIAN_POINT('',(-77.4247890138574,-71.8517093929554,3.));
+#7330=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,3.));
+#7331=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,3.));
+#7332=CARTESIAN_POINT('polyline point',(-201.181545770614,-120.015430341809,
+3.));
+#7333=CARTESIAN_POINT('polyline point',(-201.181545770614,-81.3111688524149,
+3.));
+#7334=CARTESIAN_POINT('polyline point',(-67.1815457706141,-120.015430341809,
+3.));
+#7335=CARTESIAN_POINT('polyline point',(-67.1815457706142,-81.3111688524149,
+3.));
+#7336=CARTESIAN_POINT('Origin',(-134.181545770614,48.5176714084239,3.));
+#7337=CARTESIAN_POINT('',(-201.181545770614,-113.148651615265,3.));
+#7338=CARTESIAN_POINT('',(-67.1815457706141,-113.148651615265,3.));
+#7339=CARTESIAN_POINT('Origin',(-134.181545770614,66.0176714084239,3.));
+#7340=CARTESIAN_POINT('',(-201.181545770614,-95.6486516152655,3.));
+#7341=CARTESIAN_POINT('',(-67.1815457706142,-95.6486516152656,3.));
+#7342=CARTESIAN_POINT('Origin',(-134.181545770614,-108.982328591576,3.));
+#7343=CARTESIAN_POINT('Origin',(-109.181545770614,-107.187409348464,3.));
+#7344=CARTESIAN_POINT('Origin',(-84.1815457706143,-101.68742690406,3.));
+#7345=CARTESIAN_POINT('Origin',(-184.181545770614,-101.68742690406,3.));
+#7346=CARTESIAN_POINT('Origin',(-159.181545770614,-107.187409348464,3.));
+#7347=CARTESIAN_POINT('polyline point',(-129.181545770614,-104.982328591576,
+3.));
+#7348=CARTESIAN_POINT('polyline point',(-139.181545770614,-104.982328591576,
+3.));
+#7349=CARTESIAN_POINT('polyline point',(-139.181545770614,-104.982328591576,
+3.));
+#7350=CARTESIAN_POINT('polyline point',(-139.181545770614,-102.982328591576,
+3.));
+#7351=CARTESIAN_POINT('polyline point',(-139.181545770614,-102.982328591576,
+3.));
+#7352=CARTESIAN_POINT('polyline point',(-129.181545770614,-102.982328591576,
+3.));
+#7353=CARTESIAN_POINT('polyline point',(-129.181545770614,-102.982328591576,
+3.));
+#7354=CARTESIAN_POINT('polyline point',(-129.181545770614,-104.982328591576,
+3.));
+#7355=CARTESIAN_POINT('polyline point',(-109.181545770614,-103.187409348464,
+3.));
+#7356=CARTESIAN_POINT('polyline point',(-104.181545770614,-103.187409348464,
+3.));
+#7357=CARTESIAN_POINT('polyline point',(-104.181545770614,-103.187409348464,
+3.));
+#7358=CARTESIAN_POINT('polyline point',(-104.181545770614,-101.187409348464,
+3.));
+#7359=CARTESIAN_POINT('polyline point',(-104.181545770614,-101.187409348464,
+3.));
+#7360=CARTESIAN_POINT('polyline point',(-109.181545770614,-101.187409348464,
+3.));
+#7361=CARTESIAN_POINT('polyline point',(-109.181545770614,-103.187409348464,
+3.));
+#7362=CARTESIAN_POINT('polyline point',(-114.181545770614,-103.187409348464,
+3.));
+#7363=CARTESIAN_POINT('polyline point',(-114.181545770614,-101.187409348464,
+3.));
+#7364=CARTESIAN_POINT('polyline point',(-109.181545770614,-101.187409348464,
+3.));
+#7365=CARTESIAN_POINT('polyline point',(-114.181545770614,-103.187409348464,
+3.));
+#7366=CARTESIAN_POINT('polyline point',(-114.181545770614,-101.187409348464,
+3.));
+#7367=CARTESIAN_POINT('polyline point',(-84.1815457706143,-97.68742690406,
+3.));
+#7368=CARTESIAN_POINT('polyline point',(-79.1815457706143,-97.68742690406,
+3.));
+#7369=CARTESIAN_POINT('polyline point',(-79.1815457706143,-97.68742690406,
+3.));
+#7370=CARTESIAN_POINT('polyline point',(-79.1815457706143,-95.68742690406,
+3.));
+#7371=CARTESIAN_POINT('polyline point',(-79.1815457706143,-95.68742690406,
+3.));
+#7372=CARTESIAN_POINT('polyline point',(-84.1815457706143,-95.68742690406,
+3.));
+#7373=CARTESIAN_POINT('polyline point',(-84.1815457706143,-97.68742690406,
+3.));
+#7374=CARTESIAN_POINT('polyline point',(-89.1815457706143,-97.68742690406,
+3.));
+#7375=CARTESIAN_POINT('polyline point',(-89.1815457706143,-97.68742690406,
+3.));
+#7376=CARTESIAN_POINT('polyline point',(-89.1815457706143,-95.68742690406,
+3.));
+#7377=CARTESIAN_POINT('polyline point',(-89.1815457706143,-95.68742690406,
+3.));
+#7378=CARTESIAN_POINT('polyline point',(-84.1815457706143,-95.68742690406,
+3.));
+#7379=CARTESIAN_POINT('polyline point',(-179.181545770614,-97.6874269040599,
+3.));
+#7380=CARTESIAN_POINT('polyline point',(-179.181545770614,-95.6874269040599,
+3.));
+#7381=CARTESIAN_POINT('polyline point',(-184.181545770614,-97.6874269040601,
+3.));
+#7382=CARTESIAN_POINT('polyline point',(-179.181545770614,-97.6874269040599,
+3.));
+#7383=CARTESIAN_POINT('polyline point',(-179.181545770614,-95.6874269040599,
+3.));
+#7384=CARTESIAN_POINT('polyline point',(-184.181545770614,-95.6874269040599,
+3.));
+#7385=CARTESIAN_POINT('polyline point',(-184.181545770614,-97.6874269040601,
+3.));
+#7386=CARTESIAN_POINT('polyline point',(-189.181545770614,-97.6874269040599,
+3.));
+#7387=CARTESIAN_POINT('polyline point',(-189.181545770614,-95.6874269040599,
+3.));
+#7388=CARTESIAN_POINT('polyline point',(-184.181545770614,-95.6874269040599,
+3.));
+#7389=CARTESIAN_POINT('polyline point',(-189.181545770614,-97.6874269040599,
+3.));
+#7390=CARTESIAN_POINT('polyline point',(-189.181545770614,-95.6874269040599,
+3.));
+#7391=CARTESIAN_POINT('polyline point',(-154.181545770614,-103.187409348464,
+3.));
+#7392=CARTESIAN_POINT('polyline point',(-154.181545770614,-101.187409348464,
+3.));
+#7393=CARTESIAN_POINT('polyline point',(-159.181545770614,-103.187409348464,
+3.));
+#7394=CARTESIAN_POINT('polyline point',(-154.181545770614,-103.187409348464,
+3.));
+#7395=CARTESIAN_POINT('polyline point',(-154.181545770614,-101.187409348464,
+3.));
+#7396=CARTESIAN_POINT('polyline point',(-159.181545770614,-101.187409348464,
+3.));
+#7397=CARTESIAN_POINT('polyline point',(-164.181545770614,-101.187409348464,
+3.));
+#7398=CARTESIAN_POINT('polyline point',(-159.181545770614,-101.187409348464,
+3.));
+#7399=CARTESIAN_POINT('polyline point',(-159.181545770614,-103.187409348464,
+3.));
+#7400=CARTESIAN_POINT('polyline point',(-164.181545770614,-103.187409348464,
+3.));
+#7401=CARTESIAN_POINT('polyline point',(-164.181545770614,-103.187409348464,
+3.));
+#7402=CARTESIAN_POINT('polyline point',(-164.181545770614,-101.187409348464,
+3.));
+#7403=CARTESIAN_POINT('polyline point',(-109.181545770614,-124.687409348463,
+3.));
+#7404=CARTESIAN_POINT('polyline point',(-103.681545770614,-124.687409348463,
+3.));
+#7405=CARTESIAN_POINT('polyline point',(-103.681545770614,-124.687409348463,
+3.));
+#7406=CARTESIAN_POINT('polyline point',(-103.681545770614,-131.687409348463,
+3.));
+#7407=CARTESIAN_POINT('polyline point',(-103.681545770614,-131.687409348463,
+3.));
+#7408=CARTESIAN_POINT('polyline point',(-109.181545770614,-131.687409348463,
+3.));
+#7409=CARTESIAN_POINT('polyline point',(-109.181545770614,-124.687409348463,
+3.));
+#7410=CARTESIAN_POINT('polyline point',(-114.681545770614,-124.687409348463,
+3.));
+#7411=CARTESIAN_POINT('polyline point',(-114.681545770614,-131.687409348463,
+3.));
+#7412=CARTESIAN_POINT('polyline point',(-109.181545770614,-131.687409348463,
+3.));
+#7413=CARTESIAN_POINT('polyline point',(-114.681545770614,-124.687409348463,
+3.));
+#7414=CARTESIAN_POINT('polyline point',(-114.681545770614,-131.687409348463,
+3.));
+#7415=CARTESIAN_POINT('polyline point',(-128.681545770614,-126.482328591575,
+3.));
+#7416=CARTESIAN_POINT('polyline point',(-134.181545770614,-126.482328591575,
+3.));
+#7417=CARTESIAN_POINT('polyline point',(-128.681545770614,-126.482328591575,
+3.));
+#7418=CARTESIAN_POINT('polyline point',(-128.681545770614,-133.482328591575,
+3.));
+#7419=CARTESIAN_POINT('polyline point',(-128.681545770614,-133.482328591575,
+3.));
+#7420=CARTESIAN_POINT('polyline point',(-134.181545770614,-133.482328591575,
+3.));
+#7421=CARTESIAN_POINT('polyline point',(-139.681545770614,-126.482328591575,
+3.));
+#7422=CARTESIAN_POINT('polyline point',(-134.181545770614,-126.482328591575,
+3.));
+#7423=CARTESIAN_POINT('polyline point',(-139.681545770614,-133.482328591575,
+3.));
+#7424=CARTESIAN_POINT('polyline point',(-134.181545770614,-133.482328591575,
+3.));
+#7425=CARTESIAN_POINT('polyline point',(-139.681545770614,-126.482328591575,
+3.));
+#7426=CARTESIAN_POINT('polyline point',(-139.681545770614,-133.482328591575,
+3.));
+#7427=CARTESIAN_POINT('polyline point',(-84.1815457706143,-119.18742690406,
+3.));
+#7428=CARTESIAN_POINT('polyline point',(-78.6815457706143,-119.18742690406,
+3.));
+#7429=CARTESIAN_POINT('polyline point',(-78.6815457706143,-119.18742690406,
+3.));
+#7430=CARTESIAN_POINT('polyline point',(-78.6815457706143,-126.18742690406,
+3.));
+#7431=CARTESIAN_POINT('polyline point',(-78.6815457706143,-126.18742690406,
+3.));
+#7432=CARTESIAN_POINT('polyline point',(-84.1815457706143,-126.18742690406,
+3.));
+#7433=CARTESIAN_POINT('polyline point',(-84.1815457706143,-119.18742690406,
+3.));
+#7434=CARTESIAN_POINT('polyline point',(-89.6815457706142,-119.18742690406,
+3.));
+#7435=CARTESIAN_POINT('polyline point',(-89.6815457706142,-119.18742690406,
+3.));
+#7436=CARTESIAN_POINT('polyline point',(-89.6815457706142,-126.18742690406,
+3.));
+#7437=CARTESIAN_POINT('polyline point',(-89.6815457706142,-126.18742690406,
+3.));
+#7438=CARTESIAN_POINT('polyline point',(-84.1815457706143,-126.18742690406,
+3.));
+#7439=CARTESIAN_POINT('polyline point',(-178.681545770614,-119.18742690406,
+3.));
+#7440=CARTESIAN_POINT('polyline point',(-178.681545770614,-126.18742690406,
+3.));
+#7441=CARTESIAN_POINT('polyline point',(-184.181545770614,-119.18742690406,
+3.));
+#7442=CARTESIAN_POINT('polyline point',(-178.681545770614,-119.18742690406,
+3.));
+#7443=CARTESIAN_POINT('polyline point',(-189.681545770614,-119.18742690406,
+3.));
+#7444=CARTESIAN_POINT('polyline point',(-189.681545770614,-126.18742690406,
+3.));
+#7445=CARTESIAN_POINT('polyline point',(-184.181545770614,-119.18742690406,
+3.));
+#7446=CARTESIAN_POINT('polyline point',(-189.681545770614,-119.18742690406,
+3.));
+#7447=CARTESIAN_POINT('polyline point',(-189.681545770614,-126.18742690406,
+3.));
+#7448=CARTESIAN_POINT('polyline point',(-184.181545770614,-126.18742690406,
+3.));
+#7449=CARTESIAN_POINT('polyline point',(-178.681545770614,-126.18742690406,
+3.));
+#7450=CARTESIAN_POINT('polyline point',(-184.181545770614,-126.18742690406,
+3.));
+#7451=CARTESIAN_POINT('polyline point',(-159.181545770614,-124.687409348463,
+3.));
+#7452=CARTESIAN_POINT('polyline point',(-164.681545770614,-124.687409348463,
+3.));
+#7453=CARTESIAN_POINT('polyline point',(-159.181545770614,-124.687409348463,
+3.));
+#7454=CARTESIAN_POINT('polyline point',(-153.681545770614,-124.687409348463,
+3.));
+#7455=CARTESIAN_POINT('polyline point',(-153.681545770614,-131.687409348463,
+3.));
+#7456=CARTESIAN_POINT('polyline point',(-159.181545770614,-131.687409348463,
+3.));
+#7457=CARTESIAN_POINT('polyline point',(-153.681545770614,-124.687409348463,
+3.));
+#7458=CARTESIAN_POINT('polyline point',(-153.681545770614,-131.687409348463,
+3.));
+#7459=CARTESIAN_POINT('polyline point',(-164.681545770614,-124.687409348463,
+3.));
+#7460=CARTESIAN_POINT('polyline point',(-164.681545770614,-131.687409348463,
+3.));
+#7461=CARTESIAN_POINT('polyline point',(-164.681545770614,-131.687409348463,
+3.));
+#7462=CARTESIAN_POINT('polyline point',(-159.181545770614,-131.687409348463,
+3.));
+#7463=CARTESIAN_POINT('Origin',(-70.0353819140103,-122.810290591316,3.));
+#7464=CARTESIAN_POINT('Origin',(-70.8321482282875,-77.5251222106383,3.));
+#7465=CARTESIAN_POINT('Origin',(-198.327709627218,-122.810290591316,3.));
+#7466=CARTESIAN_POINT('Origin',(-197.530943312941,-77.5251222106383,3.));
+#7467=CARTESIAN_POINT('Origin',(-73.1315457706143,-105.829566219427,3.));
+#7468=CARTESIAN_POINT('Origin',(-73.1315457706143,-94.4295662194267,3.));
+#7469=CARTESIAN_POINT('Origin',(-120.131545770614,-105.829566219427,3.));
+#7470=CARTESIAN_POINT('Origin',(-120.131545770614,-94.4295662194267,3.));
+#7471=CARTESIAN_POINT('polyline point',(-134.181545770614,-121.982328591576,
+3.));
+#7472=CARTESIAN_POINT('polyline point',(-139.181545770614,-121.982328591576,
+3.));
+#7473=CARTESIAN_POINT('polyline point',(-139.181545770614,-121.982328591576,
+3.));
+#7474=CARTESIAN_POINT('polyline point',(-139.181545770614,-112.982328591576,
+3.));
+#7475=CARTESIAN_POINT('polyline point',(-139.181545770614,-112.982328591576,
+3.));
+#7476=CARTESIAN_POINT('polyline point',(-134.181545770614,-112.982328591576,
+3.));
+#7477=CARTESIAN_POINT('polyline point',(-134.181545770614,-112.982328591576,
+3.));
+#7478=CARTESIAN_POINT('polyline point',(-134.181545770614,-121.982328591576,
+3.));
+#7479=CARTESIAN_POINT('polyline point',(-109.181545770614,-120.187409348464,
+3.));
+#7480=CARTESIAN_POINT('polyline point',(-114.181545770614,-120.187409348464,
+3.));
+#7481=CARTESIAN_POINT('polyline point',(-114.181545770614,-120.187409348464,
+3.));
+#7482=CARTESIAN_POINT('polyline point',(-114.181545770614,-111.187409348464,
+3.));
+#7483=CARTESIAN_POINT('polyline point',(-114.181545770614,-111.187409348464,
+3.));
+#7484=CARTESIAN_POINT('polyline point',(-109.181545770614,-111.187409348464,
+3.));
+#7485=CARTESIAN_POINT('polyline point',(-109.181545770614,-111.187409348464,
+3.));
+#7486=CARTESIAN_POINT('polyline point',(-109.181545770614,-120.187409348464,
+3.));
+#7487=CARTESIAN_POINT('polyline point',(-84.1815457706141,-114.68742690406,
+3.));
+#7488=CARTESIAN_POINT('polyline point',(-89.1815457706141,-114.68742690406,
+3.));
+#7489=CARTESIAN_POINT('polyline point',(-89.1815457706141,-114.68742690406,
+3.));
+#7490=CARTESIAN_POINT('polyline point',(-89.1815457706141,-105.68742690406,
+3.));
+#7491=CARTESIAN_POINT('polyline point',(-89.1815457706141,-105.68742690406,
+3.));
+#7492=CARTESIAN_POINT('polyline point',(-84.1815457706141,-105.68742690406,
+3.));
+#7493=CARTESIAN_POINT('polyline point',(-84.1815457706141,-105.68742690406,
+3.));
+#7494=CARTESIAN_POINT('polyline point',(-84.1815457706141,-114.68742690406,
+3.));
+#7495=CARTESIAN_POINT('polyline point',(-184.181545770614,-114.68742690406,
+3.));
+#7496=CARTESIAN_POINT('polyline point',(-189.181545770614,-114.68742690406,
+3.));
+#7497=CARTESIAN_POINT('polyline point',(-189.181545770614,-114.68742690406,
+3.));
+#7498=CARTESIAN_POINT('polyline point',(-189.181545770614,-105.68742690406,
+3.));
+#7499=CARTESIAN_POINT('polyline point',(-189.181545770614,-105.68742690406,
+3.));
+#7500=CARTESIAN_POINT('polyline point',(-184.181545770614,-105.68742690406,
+3.));
+#7501=CARTESIAN_POINT('polyline point',(-184.181545770614,-105.68742690406,
+3.));
+#7502=CARTESIAN_POINT('polyline point',(-184.181545770614,-114.68742690406,
+3.));
+#7503=CARTESIAN_POINT('polyline point',(-159.181545770614,-120.187409348464,
+3.));
+#7504=CARTESIAN_POINT('polyline point',(-164.181545770614,-120.187409348464,
+3.));
+#7505=CARTESIAN_POINT('polyline point',(-164.181545770614,-120.187409348464,
+3.));
+#7506=CARTESIAN_POINT('polyline point',(-164.181545770614,-111.187409348464,
+3.));
+#7507=CARTESIAN_POINT('polyline point',(-164.181545770614,-111.187409348464,
+3.));
+#7508=CARTESIAN_POINT('polyline point',(-159.181545770614,-111.187409348464,
+3.));
+#7509=CARTESIAN_POINT('polyline point',(-159.181545770614,-111.187409348464,
+3.));
+#7510=CARTESIAN_POINT('polyline point',(-159.181545770614,-120.187409348464,
+3.));
+#7511=CARTESIAN_POINT('',(0.,0.,3.));
+#7512=CARTESIAN_POINT('',(-66.8136445733135,-74.5499535809703,3.));
+#7513=CARTESIAN_POINT('',(-159.181545770614,-125.188933033705,3.));
+#7514=CARTESIAN_POINT('',(-159.181545770614,-111.187409348464,3.));
+#7515=CARTESIAN_POINT('',(-134.181545770614,-112.982328591576,3.));
+#7516=CARTESIAN_POINT('',(-109.181545770614,-111.187409348464,3.));
+#7517=CARTESIAN_POINT('',(-89.1815457706141,-105.829566219427,3.));
+#7518=CARTESIAN_POINT('',(-84.1815457706142,-105.829566219427,3.));
+#7519=CARTESIAN_POINT('',(-84.1815457706141,-105.68742690406,3.));
+#7520=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#7524,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#7521=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#7524,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#7522=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7520))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#7524,#7526,#7527))
+REPRESENTATION_CONTEXT('','3D')
+);
+#7523=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7521))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#7524,#7526,#7527))
+REPRESENTATION_CONTEXT('','3D')
+);
+#7524=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.MILLI.,.METRE.)
+);
+#7525=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.CENTI.,.METRE.)
+);
+#7526=(
+NAMED_UNIT(*)
+PLANE_ANGLE_UNIT()
+SI_UNIT($,.RADIAN.)
+);
+#7527=(
+NAMED_UNIT(*)
+SI_UNIT($,.STERADIAN.)
+SOLID_ANGLE_UNIT()
+);
+#7528=SHAPE_DEFINITION_REPRESENTATION(#7529,#7530);
+#7529=PRODUCT_DEFINITION_SHAPE('',$,#7532);
+#7530=SHAPE_REPRESENTATION('',(#3604),#7522);
+#7531=PRODUCT_DEFINITION_CONTEXT('part definition',#7536,'design');
+#7532=PRODUCT_DEFINITION('base','base',#7533,#7531);
+#7533=PRODUCT_DEFINITION_FORMATION('',$,#7538);
+#7534=PRODUCT_RELATED_PRODUCT_CATEGORY('base','base',(#7538));
+#7535=APPLICATION_PROTOCOL_DEFINITION('international standard',
+'automotive_design',2009,#7536);
+#7536=APPLICATION_CONTEXT(
+'Core Data for Automotive Mechanical Design Process');
+#7537=PRODUCT_CONTEXT('part definition',#7536,'mechanical');
+#7538=PRODUCT('base','base',$,(#7537));
+#7539=PRESENTATION_STYLE_ASSIGNMENT((#7543));
+#7540=PRESENTATION_STYLE_ASSIGNMENT((#7544));
+#7541=PRESENTATION_STYLE_ASSIGNMENT((#7545));
+#7542=PRESENTATION_STYLE_ASSIGNMENT((#7546));
+#7543=SURFACE_STYLE_USAGE(.BOTH.,#7549);
+#7544=SURFACE_STYLE_USAGE(.BOTH.,#7550);
+#7545=SURFACE_STYLE_USAGE(.BOTH.,#7551);
+#7546=SURFACE_STYLE_USAGE(.BOTH.,#7552);
+#7547=SURFACE_STYLE_RENDERING_WITH_PROPERTIES($,#7565,(#7548));
+#7548=SURFACE_STYLE_TRANSPARENT(0.);
+#7549=SURFACE_SIDE_STYLE('',(#7553,#7547));
+#7550=SURFACE_SIDE_STYLE('',(#7554));
+#7551=SURFACE_SIDE_STYLE('',(#7555));
+#7552=SURFACE_SIDE_STYLE('',(#7556));
+#7553=SURFACE_STYLE_FILL_AREA(#7557);
+#7554=SURFACE_STYLE_FILL_AREA(#7558);
+#7555=SURFACE_STYLE_FILL_AREA(#7559);
+#7556=SURFACE_STYLE_FILL_AREA(#7560);
+#7557=FILL_AREA_STYLE('',(#7561));
+#7558=FILL_AREA_STYLE('',(#7562));
+#7559=FILL_AREA_STYLE('',(#7563));
+#7560=FILL_AREA_STYLE('',(#7564));
+#7561=FILL_AREA_STYLE_COLOUR('',#7565);
+#7562=FILL_AREA_STYLE_COLOUR('',#7566);
+#7563=FILL_AREA_STYLE_COLOUR('',#7567);
+#7564=FILL_AREA_STYLE_COLOUR('',#7568);
+#7565=COLOUR_RGB('',0.749019607843137,0.749019607843137,0.749019607843137);
+#7566=COLOUR_RGB('',1.,1.,0.);
+#7567=COLOUR_RGB('',1.,0.,1.);
+#7568=COLOUR_RGB('',0.,0.,0.501960784313725);
+ENDSEC;
+END-ISO-10303-21;
diff --git a/Komponenten/deckel.ipt b/Komponenten/deckel.ipt
new file mode 100644
index 0000000000000000000000000000000000000000..e9dfa83d9d4bb590cdcc8f44c017e579395fc241
Binary files /dev/null and b/Komponenten/deckel.ipt differ
diff --git a/Komponenten/deckel.stp b/Komponenten/deckel.stp
new file mode 100644
index 0000000000000000000000000000000000000000..20239a40262fb9c53f43e867bb6609a9a0cf61d2
--- /dev/null
+++ b/Komponenten/deckel.stp
@@ -0,0 +1,2849 @@
+ISO-10303-21;
+HEADER;
+/* Generated by software containing ST-Developer
+ * from STEP Tools, Inc. (www.steptools.com) 
+ */
+
+FILE_DESCRIPTION(
+/* description */ (''),
+/* implementation_level */ '2;1');
+
+FILE_NAME(
+/* name */ 'deckel.stp',
+/* time_stamp */ '2025-01-13T19:50:24+01:00',
+/* author */ ('seb'),
+/* organization */ (''),
+/* preprocessor_version */ 'ST-DEVELOPER v20',
+/* originating_system */ 'Autodesk Inventor 2025',
+/* authorisation */ '');
+
+FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }'));
+ENDSEC;
+
+DATA;
+#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#17),#2731);
+#11=GEOMETRICALLY_BOUNDED_WIREFRAME_SHAPE_REPRESENTATION('',(#12,#13),#2730);
+#12=GEOMETRIC_CURVE_SET('Skizze4',(#2726));
+#13=GEOMETRIC_CURVE_SET('Skizze5',(#2727));
+#14=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#2738,#16);
+#15=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#2738,#11);
+#16=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#18),#2730);
+#17=STYLED_ITEM('',(#2747),#18);
+#18=MANIFOLD_SOLID_BREP('Volumenk\X\F6rper1',#1494);
+#19=TOROIDAL_SURFACE('',#1582,3.99999999999997,1.99999999999997);
+#20=TOROIDAL_SURFACE('',#1589,4.,2.);
+#21=TOROIDAL_SURFACE('',#1595,173.,2.);
+#22=TOROIDAL_SURFACE('',#1598,8.,2.);
+#23=TOROIDAL_SURFACE('',#1603,8.,2.);
+#24=TOROIDAL_SURFACE('',#1606,177.000000000002,2.);
+#25=TOROIDAL_SURFACE('',#1609,8.,2.);
+#26=TOROIDAL_SURFACE('',#1614,8.,2.);
+#27=TOROIDAL_SURFACE('',#1617,173.,2.);
+#28=SPHERICAL_SURFACE('',#1570,1.99999999999999);
+#29=SPHERICAL_SURFACE('',#1576,2.);
+#30=FACE_BOUND('',#150,.T.);
+#31=FACE_BOUND('',#153,.T.);
+#32=FACE_BOUND('',#156,.T.);
+#33=FACE_BOUND('',#159,.T.);
+#34=FACE_BOUND('',#196,.T.);
+#35=FACE_BOUND('',#203,.T.);
+#36=FACE_BOUND('',#204,.T.);
+#37=FACE_BOUND('',#205,.T.);
+#38=FACE_BOUND('',#206,.T.);
+#39=FACE_BOUND('',#233,.T.);
+#40=PLANE('',#1520);
+#41=PLANE('',#1526);
+#42=PLANE('',#1532);
+#43=PLANE('',#1538);
+#44=PLANE('',#1540);
+#45=PLANE('',#1557);
+#46=PLANE('',#1561);
+#47=PLANE('',#1565);
+#48=PLANE('',#1569);
+#49=PLANE('',#1627);
+#50=PLANE('',#1638);
+#51=PLANE('',#1651);
+#52=PLANE('',#1652);
+#53=PLANE('',#1672);
+#54=PLANE('',#1677);
+#55=PLANE('',#1686);
+#56=PLANE('',#1687);
+#57=PLANE('',#1696);
+#58=PLANE('',#1699);
+#59=PLANE('',#1704);
+#60=PLANE('',#1712);
+#61=PLANE('',#1713);
+#62=PLANE('',#1714);
+#63=PLANE('',#1716);
+#64=PLANE('',#1717);
+#65=PLANE('',#1718);
+#66=FACE_OUTER_BOUND('',#148,.T.);
+#67=FACE_OUTER_BOUND('',#149,.T.);
+#68=FACE_OUTER_BOUND('',#151,.T.);
+#69=FACE_OUTER_BOUND('',#152,.T.);
+#70=FACE_OUTER_BOUND('',#154,.T.);
+#71=FACE_OUTER_BOUND('',#155,.T.);
+#72=FACE_OUTER_BOUND('',#157,.T.);
+#73=FACE_OUTER_BOUND('',#158,.T.);
+#74=FACE_OUTER_BOUND('',#160,.T.);
+#75=FACE_OUTER_BOUND('',#161,.T.);
+#76=FACE_OUTER_BOUND('',#162,.T.);
+#77=FACE_OUTER_BOUND('',#163,.T.);
+#78=FACE_OUTER_BOUND('',#164,.T.);
+#79=FACE_OUTER_BOUND('',#165,.T.);
+#80=FACE_OUTER_BOUND('',#166,.T.);
+#81=FACE_OUTER_BOUND('',#167,.T.);
+#82=FACE_OUTER_BOUND('',#168,.T.);
+#83=FACE_OUTER_BOUND('',#169,.T.);
+#84=FACE_OUTER_BOUND('',#170,.T.);
+#85=FACE_OUTER_BOUND('',#171,.T.);
+#86=FACE_OUTER_BOUND('',#172,.T.);
+#87=FACE_OUTER_BOUND('',#173,.T.);
+#88=FACE_OUTER_BOUND('',#174,.T.);
+#89=FACE_OUTER_BOUND('',#175,.T.);
+#90=FACE_OUTER_BOUND('',#176,.T.);
+#91=FACE_OUTER_BOUND('',#177,.T.);
+#92=FACE_OUTER_BOUND('',#178,.T.);
+#93=FACE_OUTER_BOUND('',#179,.T.);
+#94=FACE_OUTER_BOUND('',#180,.T.);
+#95=FACE_OUTER_BOUND('',#181,.T.);
+#96=FACE_OUTER_BOUND('',#182,.T.);
+#97=FACE_OUTER_BOUND('',#183,.T.);
+#98=FACE_OUTER_BOUND('',#184,.T.);
+#99=FACE_OUTER_BOUND('',#185,.T.);
+#100=FACE_OUTER_BOUND('',#186,.T.);
+#101=FACE_OUTER_BOUND('',#187,.T.);
+#102=FACE_OUTER_BOUND('',#188,.T.);
+#103=FACE_OUTER_BOUND('',#189,.T.);
+#104=FACE_OUTER_BOUND('',#190,.T.);
+#105=FACE_OUTER_BOUND('',#191,.T.);
+#106=FACE_OUTER_BOUND('',#192,.T.);
+#107=FACE_OUTER_BOUND('',#193,.T.);
+#108=FACE_OUTER_BOUND('',#194,.T.);
+#109=FACE_OUTER_BOUND('',#195,.T.);
+#110=FACE_OUTER_BOUND('',#197,.T.);
+#111=FACE_OUTER_BOUND('',#198,.T.);
+#112=FACE_OUTER_BOUND('',#199,.T.);
+#113=FACE_OUTER_BOUND('',#200,.T.);
+#114=FACE_OUTER_BOUND('',#201,.T.);
+#115=FACE_OUTER_BOUND('',#202,.T.);
+#116=FACE_OUTER_BOUND('',#207,.T.);
+#117=FACE_OUTER_BOUND('',#208,.T.);
+#118=FACE_OUTER_BOUND('',#209,.T.);
+#119=FACE_OUTER_BOUND('',#210,.T.);
+#120=FACE_OUTER_BOUND('',#211,.T.);
+#121=FACE_OUTER_BOUND('',#212,.T.);
+#122=FACE_OUTER_BOUND('',#213,.T.);
+#123=FACE_OUTER_BOUND('',#214,.T.);
+#124=FACE_OUTER_BOUND('',#215,.T.);
+#125=FACE_OUTER_BOUND('',#216,.T.);
+#126=FACE_OUTER_BOUND('',#217,.T.);
+#127=FACE_OUTER_BOUND('',#218,.T.);
+#128=FACE_OUTER_BOUND('',#219,.T.);
+#129=FACE_OUTER_BOUND('',#220,.T.);
+#130=FACE_OUTER_BOUND('',#221,.T.);
+#131=FACE_OUTER_BOUND('',#222,.T.);
+#132=FACE_OUTER_BOUND('',#223,.T.);
+#133=FACE_OUTER_BOUND('',#224,.T.);
+#134=FACE_OUTER_BOUND('',#225,.T.);
+#135=FACE_OUTER_BOUND('',#226,.T.);
+#136=FACE_OUTER_BOUND('',#227,.T.);
+#137=FACE_OUTER_BOUND('',#228,.T.);
+#138=FACE_OUTER_BOUND('',#229,.T.);
+#139=FACE_OUTER_BOUND('',#230,.T.);
+#140=FACE_OUTER_BOUND('',#231,.T.);
+#141=FACE_OUTER_BOUND('',#232,.T.);
+#142=FACE_OUTER_BOUND('',#234,.T.);
+#143=FACE_OUTER_BOUND('',#235,.T.);
+#144=FACE_OUTER_BOUND('',#236,.T.);
+#145=FACE_OUTER_BOUND('',#237,.T.);
+#146=FACE_OUTER_BOUND('',#238,.T.);
+#147=FACE_OUTER_BOUND('',#239,.T.);
+#148=EDGE_LOOP('',(#923,#924,#925,#926,#927,#928));
+#149=EDGE_LOOP('',(#929));
+#150=EDGE_LOOP('',(#930));
+#151=EDGE_LOOP('',(#931,#932,#933,#934,#935,#936));
+#152=EDGE_LOOP('',(#937));
+#153=EDGE_LOOP('',(#938));
+#154=EDGE_LOOP('',(#939,#940,#941,#942,#943,#944));
+#155=EDGE_LOOP('',(#945));
+#156=EDGE_LOOP('',(#946));
+#157=EDGE_LOOP('',(#947,#948,#949,#950,#951,#952));
+#158=EDGE_LOOP('',(#953));
+#159=EDGE_LOOP('',(#954));
+#160=EDGE_LOOP('',(#955,#956,#957,#958,#959,#960,#961,#962,#963,#964,#965,
+#966,#967,#968,#969,#970,#971,#972,#973,#974,#975,#976,#977,#978,#979));
+#161=EDGE_LOOP('',(#980,#981,#982,#983));
+#162=EDGE_LOOP('',(#984,#985,#986,#987));
+#163=EDGE_LOOP('',(#988,#989,#990,#991));
+#164=EDGE_LOOP('',(#992,#993,#994,#995));
+#165=EDGE_LOOP('',(#996,#997,#998,#999));
+#166=EDGE_LOOP('',(#1000,#1001,#1002,#1003));
+#167=EDGE_LOOP('',(#1004,#1005,#1006,#1007));
+#168=EDGE_LOOP('',(#1008,#1009,#1010,#1011));
+#169=EDGE_LOOP('',(#1012,#1013,#1014));
+#170=EDGE_LOOP('',(#1015,#1016,#1017,#1018));
+#171=EDGE_LOOP('',(#1019,#1020,#1021));
+#172=EDGE_LOOP('',(#1022,#1023,#1024,#1025));
+#173=EDGE_LOOP('',(#1026,#1027,#1028,#1029));
+#174=EDGE_LOOP('',(#1030,#1031,#1032,#1033));
+#175=EDGE_LOOP('',(#1034,#1035,#1036,#1037));
+#176=EDGE_LOOP('',(#1038,#1039,#1040,#1041));
+#177=EDGE_LOOP('',(#1042,#1043,#1044,#1045));
+#178=EDGE_LOOP('',(#1046,#1047,#1048,#1049));
+#179=EDGE_LOOP('',(#1050,#1051,#1052,#1053,#1054,#1055));
+#180=EDGE_LOOP('',(#1056,#1057,#1058,#1059));
+#181=EDGE_LOOP('',(#1060,#1061,#1062,#1063,#1064,#1065));
+#182=EDGE_LOOP('',(#1066,#1067,#1068,#1069));
+#183=EDGE_LOOP('',(#1070,#1071,#1072,#1073,#1074,#1075));
+#184=EDGE_LOOP('',(#1076,#1077,#1078,#1079));
+#185=EDGE_LOOP('',(#1080,#1081,#1082,#1083,#1084,#1085,#1086));
+#186=EDGE_LOOP('',(#1087,#1088,#1089,#1090));
+#187=EDGE_LOOP('',(#1091,#1092,#1093,#1094));
+#188=EDGE_LOOP('',(#1095,#1096,#1097,#1098));
+#189=EDGE_LOOP('',(#1099,#1100,#1101,#1102));
+#190=EDGE_LOOP('',(#1103,#1104,#1105,#1106,#1107,#1108,#1109,#1110));
+#191=EDGE_LOOP('',(#1111,#1112,#1113,#1114));
+#192=EDGE_LOOP('',(#1115,#1116,#1117,#1118,#1119,#1120,#1121,#1122));
+#193=EDGE_LOOP('',(#1123,#1124,#1125,#1126));
+#194=EDGE_LOOP('',(#1127,#1128,#1129,#1130,#1131,#1132,#1133,#1134));
+#195=EDGE_LOOP('',(#1135,#1136,#1137,#1138));
+#196=EDGE_LOOP('',(#1139,#1140,#1141,#1142,#1143,#1144,#1145,#1146));
+#197=EDGE_LOOP('',(#1147,#1148,#1149,#1150,#1151,#1152,#1153,#1154));
+#198=EDGE_LOOP('',(#1155,#1156,#1157,#1158));
+#199=EDGE_LOOP('',(#1159,#1160,#1161,#1162));
+#200=EDGE_LOOP('',(#1163,#1164,#1165,#1166));
+#201=EDGE_LOOP('',(#1167,#1168,#1169,#1170));
+#202=EDGE_LOOP('',(#1171,#1172,#1173,#1174,#1175,#1176,#1177,#1178,#1179,
+#1180,#1181,#1182,#1183,#1184,#1185,#1186,#1187,#1188,#1189,#1190,#1191,
+#1192,#1193,#1194,#1195,#1196,#1197,#1198,#1199,#1200,#1201,#1202,#1203,
+#1204,#1205,#1206,#1207,#1208,#1209,#1210,#1211,#1212,#1213,#1214));
+#203=EDGE_LOOP('',(#1215));
+#204=EDGE_LOOP('',(#1216));
+#205=EDGE_LOOP('',(#1217));
+#206=EDGE_LOOP('',(#1218));
+#207=EDGE_LOOP('',(#1219,#1220,#1221,#1222,#1223,#1224,#1225,#1226));
+#208=EDGE_LOOP('',(#1227,#1228,#1229,#1230));
+#209=EDGE_LOOP('',(#1231,#1232,#1233,#1234));
+#210=EDGE_LOOP('',(#1235,#1236,#1237,#1238));
+#211=EDGE_LOOP('',(#1239,#1240,#1241,#1242));
+#212=EDGE_LOOP('',(#1243,#1244));
+#213=EDGE_LOOP('',(#1245,#1246,#1247,#1248));
+#214=EDGE_LOOP('',(#1249,#1250,#1251,#1252));
+#215=EDGE_LOOP('',(#1253,#1254,#1255,#1256));
+#216=EDGE_LOOP('',(#1257,#1258,#1259,#1260));
+#217=EDGE_LOOP('',(#1261,#1262));
+#218=EDGE_LOOP('',(#1263,#1264));
+#219=EDGE_LOOP('',(#1265,#1266,#1267,#1268));
+#220=EDGE_LOOP('',(#1269,#1270,#1271,#1272));
+#221=EDGE_LOOP('',(#1273,#1274,#1275,#1276));
+#222=EDGE_LOOP('',(#1277,#1278,#1279,#1280));
+#223=EDGE_LOOP('',(#1281,#1282));
+#224=EDGE_LOOP('',(#1283,#1284,#1285,#1286));
+#225=EDGE_LOOP('',(#1287,#1288,#1289,#1290));
+#226=EDGE_LOOP('',(#1291,#1292,#1293,#1294));
+#227=EDGE_LOOP('',(#1295,#1296,#1297,#1298));
+#228=EDGE_LOOP('',(#1299,#1300,#1301,#1302,#1303,#1304,#1305,#1306,#1307,
+#1308,#1309,#1310,#1311,#1312,#1313,#1314));
+#229=EDGE_LOOP('',(#1315,#1316,#1317,#1318));
+#230=EDGE_LOOP('',(#1319,#1320,#1321,#1322));
+#231=EDGE_LOOP('',(#1323,#1324,#1325,#1326));
+#232=EDGE_LOOP('',(#1327,#1328,#1329,#1330));
+#233=EDGE_LOOP('',(#1331,#1332,#1333,#1334,#1335,#1336,#1337,#1338));
+#234=EDGE_LOOP('',(#1339,#1340,#1341,#1342));
+#235=EDGE_LOOP('',(#1343,#1344,#1345,#1346));
+#236=EDGE_LOOP('',(#1347,#1348,#1349,#1350));
+#237=EDGE_LOOP('',(#1351,#1352,#1353,#1354));
+#238=EDGE_LOOP('',(#1355,#1356,#1357,#1358,#1359,#1360,#1361,#1362));
+#239=EDGE_LOOP('',(#1363,#1364,#1365,#1366));
+#240=LINE('',#2247,#337);
+#241=LINE('',#2274,#338);
+#242=LINE('',#2302,#339);
+#243=LINE('',#2326,#340);
+#244=LINE('',#2340,#341);
+#245=LINE('',#2342,#342);
+#246=LINE('',#2344,#343);
+#247=LINE('',#2353,#344);
+#248=LINE('',#2363,#345);
+#249=LINE('',#2370,#346);
+#250=LINE('',#2373,#347);
+#251=LINE('',#2376,#348);
+#252=LINE('',#2378,#349);
+#253=LINE('',#2379,#350);
+#254=LINE('',#2385,#351);
+#255=LINE('',#2388,#352);
+#256=LINE('',#2390,#353);
+#257=LINE('',#2391,#354);
+#258=LINE('',#2397,#355);
+#259=LINE('',#2400,#356);
+#260=LINE('',#2402,#357);
+#261=LINE('',#2403,#358);
+#262=LINE('',#2408,#359);
+#263=LINE('',#2411,#360);
+#264=LINE('',#2412,#361);
+#265=LINE('',#2423,#362);
+#266=LINE('',#2424,#363);
+#267=LINE('',#2435,#364);
+#268=LINE('',#2436,#365);
+#269=LINE('',#2447,#366);
+#270=LINE('',#2448,#367);
+#271=LINE('',#2450,#368);
+#272=LINE('',#2461,#369);
+#273=LINE('',#2462,#370);
+#274=LINE('',#2474,#371);
+#275=LINE('',#2490,#372);
+#276=LINE('',#2498,#373);
+#277=LINE('',#2500,#374);
+#278=LINE('',#2503,#375);
+#279=LINE('',#2507,#376);
+#280=LINE('',#2511,#377);
+#281=LINE('',#2515,#378);
+#282=LINE('',#2519,#379);
+#283=LINE('',#2520,#380);
+#284=LINE('',#2523,#381);
+#285=LINE('',#2527,#382);
+#286=LINE('',#2531,#383);
+#287=LINE('',#2535,#384);
+#288=LINE('',#2539,#385);
+#289=LINE('',#2543,#386);
+#290=LINE('',#2547,#387);
+#291=LINE('',#2551,#388);
+#292=LINE('',#2552,#389);
+#293=LINE('',#2555,#390);
+#294=LINE('',#2559,#391);
+#295=LINE('',#2563,#392);
+#296=LINE('',#2570,#393);
+#297=LINE('',#2574,#394);
+#298=LINE('',#2579,#395);
+#299=LINE('',#2583,#396);
+#300=LINE('',#2586,#397);
+#301=LINE('',#2587,#398);
+#302=LINE('',#2589,#399);
+#303=LINE('',#2594,#400);
+#304=LINE('',#2595,#401);
+#305=LINE('',#2597,#402);
+#306=LINE('',#2599,#403);
+#307=LINE('',#2605,#404);
+#308=LINE('',#2621,#405);
+#309=LINE('',#2627,#406);
+#310=LINE('',#2628,#407);
+#311=LINE('',#2629,#408);
+#312=LINE('',#2640,#409);
+#313=LINE('',#2642,#410);
+#314=LINE('',#2643,#411);
+#315=LINE('',#2645,#412);
+#316=LINE('',#2647,#413);
+#317=LINE('',#2649,#414);
+#318=LINE('',#2651,#415);
+#319=LINE('',#2657,#416);
+#320=LINE('',#2659,#417);
+#321=LINE('',#2665,#418);
+#322=LINE('',#2667,#419);
+#323=LINE('',#2675,#420);
+#324=LINE('',#2678,#421);
+#325=LINE('',#2683,#422);
+#326=LINE('',#2685,#423);
+#327=LINE('',#2690,#424);
+#328=LINE('',#2694,#425);
+#329=LINE('',#2695,#426);
+#330=LINE('',#2699,#427);
+#331=LINE('',#2702,#428);
+#332=LINE('',#2705,#429);
+#333=LINE('',#2707,#430);
+#334=LINE('',#2713,#431);
+#335=LINE('',#2715,#432);
+#336=LINE('',#2721,#433);
+#337=VECTOR('',#1725,3.75);
+#338=VECTOR('',#1736,3.75);
+#339=VECTOR('',#1749,3.75);
+#340=VECTOR('',#1762,3.75);
+#341=VECTOR('',#1779,10.);
+#342=VECTOR('',#1780,10.);
+#343=VECTOR('',#1781,10.);
+#344=VECTOR('',#1790,10.);
+#345=VECTOR('',#1801,10.);
+#346=VECTOR('',#1808,10.);
+#347=VECTOR('',#1811,10.);
+#348=VECTOR('',#1814,10.);
+#349=VECTOR('',#1815,10.);
+#350=VECTOR('',#1816,10.);
+#351=VECTOR('',#1821,10.);
+#352=VECTOR('',#1824,10.);
+#353=VECTOR('',#1827,10.);
+#354=VECTOR('',#1828,10.);
+#355=VECTOR('',#1833,10.);
+#356=VECTOR('',#1836,10.);
+#357=VECTOR('',#1839,10.);
+#358=VECTOR('',#1840,10.);
+#359=VECTOR('',#1845,10.);
+#360=VECTOR('',#1850,10.);
+#361=VECTOR('',#1851,10.);
+#362=VECTOR('',#1864,10.);
+#363=VECTOR('',#1865,10.);
+#364=VECTOR('',#1878,10.);
+#365=VECTOR('',#1879,10.);
+#366=VECTOR('',#1892,10.);
+#367=VECTOR('',#1893,10.);
+#368=VECTOR('',#1896,10.);
+#369=VECTOR('',#1909,10.);
+#370=VECTOR('',#1910,10.);
+#371=VECTOR('',#1927,10.);
+#372=VECTOR('',#1950,10.);
+#373=VECTOR('',#1963,10.);
+#374=VECTOR('',#1966,10.);
+#375=VECTOR('',#1969,10.);
+#376=VECTOR('',#1974,10.);
+#377=VECTOR('',#1977,10.);
+#378=VECTOR('',#1980,10.);
+#379=VECTOR('',#1985,10.);
+#380=VECTOR('',#1986,10.);
+#381=VECTOR('',#1989,10.);
+#382=VECTOR('',#1992,10.);
+#383=VECTOR('',#1995,10.);
+#384=VECTOR('',#2000,10.);
+#385=VECTOR('',#2005,10.);
+#386=VECTOR('',#2008,10.);
+#387=VECTOR('',#2011,10.);
+#388=VECTOR('',#2016,10.);
+#389=VECTOR('',#2017,10.);
+#390=VECTOR('',#2020,10.);
+#391=VECTOR('',#2023,10.);
+#392=VECTOR('',#2026,10.);
+#393=VECTOR('',#2035,10.);
+#394=VECTOR('',#2038,10.);
+#395=VECTOR('',#2043,10.);
+#396=VECTOR('',#2046,10.);
+#397=VECTOR('',#2051,10.);
+#398=VECTOR('',#2052,10.);
+#399=VECTOR('',#2055,10.);
+#400=VECTOR('',#2064,10.);
+#401=VECTOR('',#2065,10.);
+#402=VECTOR('',#2066,10.);
+#403=VECTOR('',#2067,10.);
+#404=VECTOR('',#2072,10.);
+#405=VECTOR('',#2087,10.);
+#406=VECTOR('',#2092,10.);
+#407=VECTOR('',#2093,10.);
+#408=VECTOR('',#2094,10.);
+#409=VECTOR('',#2105,10.);
+#410=VECTOR('',#2106,10.);
+#411=VECTOR('',#2107,10.);
+#412=VECTOR('',#2110,2.5);
+#413=VECTOR('',#2113,2.5);
+#414=VECTOR('',#2116,2.5);
+#415=VECTOR('',#2119,2.5);
+#416=VECTOR('',#2128,10.);
+#417=VECTOR('',#2129,10.);
+#418=VECTOR('',#2138,10.);
+#419=VECTOR('',#2139,10.);
+#420=VECTOR('',#2152,10.);
+#421=VECTOR('',#2155,10.);
+#422=VECTOR('',#2162,10.);
+#423=VECTOR('',#2163,10.);
+#424=VECTOR('',#2170,10.);
+#425=VECTOR('',#2175,10.);
+#426=VECTOR('',#2176,10.);
+#427=VECTOR('',#2181,10.);
+#428=VECTOR('',#2184,10.);
+#429=VECTOR('',#2189,10.);
+#430=VECTOR('',#2190,10.);
+#431=VECTOR('',#2199,10.);
+#432=VECTOR('',#2202,10.);
+#433=VECTOR('',#2213,10.);
+#434=CIRCLE('',#1518,3.75);
+#435=CIRCLE('',#1519,3.75);
+#436=CIRCLE('',#1521,2.5);
+#437=CIRCLE('',#1523,3.75);
+#438=CIRCLE('',#1524,3.75);
+#439=CIRCLE('',#1525,3.75);
+#440=CIRCLE('',#1527,2.5);
+#441=CIRCLE('',#1529,3.75);
+#442=CIRCLE('',#1530,3.75);
+#443=CIRCLE('',#1531,3.75);
+#444=CIRCLE('',#1533,2.5);
+#445=CIRCLE('',#1535,3.75);
+#446=CIRCLE('',#1536,3.75);
+#447=CIRCLE('',#1537,3.75);
+#448=CIRCLE('',#1539,2.5);
+#449=CIRCLE('',#1541,8.);
+#450=CIRCLE('',#1542,173.);
+#451=CIRCLE('',#1543,3.99999999999997);
+#452=CIRCLE('',#1544,4.);
+#453=CIRCLE('',#1545,173.);
+#454=CIRCLE('',#1546,8.);
+#455=CIRCLE('',#1547,8.);
+#456=CIRCLE('',#1548,8.);
+#457=CIRCLE('',#1549,8.);
+#458=CIRCLE('',#1550,177.000000000002);
+#459=CIRCLE('',#1551,8.);
+#460=CIRCLE('',#1552,8.);
+#461=CIRCLE('',#1553,8.);
+#462=CIRCLE('',#1555,2.);
+#463=CIRCLE('',#1556,2.);
+#464=CIRCLE('',#1559,2.);
+#465=CIRCLE('',#1560,2.);
+#466=CIRCLE('',#1563,2.);
+#467=CIRCLE('',#1564,2.);
+#468=CIRCLE('',#1567,2.);
+#469=CIRCLE('',#1568,2.);
+#470=CIRCLE('',#1571,2.);
+#471=CIRCLE('',#1572,1.99999999999999);
+#472=CIRCLE('',#1573,2.);
+#473=CIRCLE('',#1575,2.);
+#474=CIRCLE('',#1577,1.99999999999999);
+#475=CIRCLE('',#1578,2.);
+#476=CIRCLE('',#1579,2.);
+#477=CIRCLE('',#1581,2.);
+#478=CIRCLE('',#1583,1.99999999999997);
+#479=CIRCLE('',#1584,2.);
+#480=CIRCLE('',#1585,2.);
+#481=CIRCLE('',#1587,2.);
+#482=CIRCLE('',#1590,2.);
+#483=CIRCLE('',#1591,2.);
+#484=CIRCLE('',#1592,2.);
+#485=CIRCLE('',#1594,2.);
+#486=CIRCLE('',#1596,1.99999999999997);
+#487=CIRCLE('',#1597,175.);
+#488=CIRCLE('',#1599,10.);
+#489=CIRCLE('',#1600,1.99999999999998);
+#490=CIRCLE('',#1602,2.00000000000001);
+#491=CIRCLE('',#1604,10.);
+#492=CIRCLE('',#1605,1.99999999999996);
+#493=CIRCLE('',#1607,1.99999999999999);
+#494=CIRCLE('',#1608,175.000000000002);
+#495=CIRCLE('',#1610,10.);
+#496=CIRCLE('',#1611,1.99999999999997);
+#497=CIRCLE('',#1613,2.);
+#498=CIRCLE('',#1615,10.);
+#499=CIRCLE('',#1616,1.99999999999998);
+#500=CIRCLE('',#1618,175.);
+#501=CIRCLE('',#1622,175.);
+#502=CIRCLE('',#1624,10.);
+#503=CIRCLE('',#1625,10.);
+#504=CIRCLE('',#1626,10.);
+#505=CIRCLE('',#1629,10.);
+#506=CIRCLE('',#1630,10.);
+#507=CIRCLE('',#1631,10.);
+#508=CIRCLE('',#1633,175.000000000002);
+#509=CIRCLE('',#1635,10.);
+#510=CIRCLE('',#1636,10.);
+#511=CIRCLE('',#1637,10.);
+#512=CIRCLE('',#1640,10.);
+#513=CIRCLE('',#1641,10.);
+#514=CIRCLE('',#1642,10.);
+#515=CIRCLE('',#1644,175.);
+#516=CIRCLE('',#1646,8.5);
+#517=CIRCLE('',#1647,8.5);
+#518=CIRCLE('',#1649,8.5);
+#519=CIRCLE('',#1650,8.5);
+#520=CIRCLE('',#1653,5.);
+#521=CIRCLE('',#1654,5.00000000000001);
+#522=CIRCLE('',#1655,5.00000000000001);
+#523=CIRCLE('',#1656,5.);
+#524=CIRCLE('',#1657,172.);
+#525=CIRCLE('',#1658,5.);
+#526=CIRCLE('',#1659,7.);
+#527=CIRCLE('',#1660,5.00000000000001);
+#528=CIRCLE('',#1661,7.);
+#529=CIRCLE('',#1662,178.000000000002);
+#530=CIRCLE('',#1663,7.);
+#531=CIRCLE('',#1664,5.00000000000001);
+#532=CIRCLE('',#1665,7.);
+#533=CIRCLE('',#1666,5.);
+#534=CIRCLE('',#1667,172.);
+#535=CIRCLE('',#1668,2.5);
+#536=CIRCLE('',#1669,2.5);
+#537=CIRCLE('',#1670,2.5);
+#538=CIRCLE('',#1671,2.5);
+#539=CIRCLE('',#1678,5.);
+#540=CIRCLE('',#1681,5.);
+#541=CIRCLE('',#1683,5.);
+#542=CIRCLE('',#1685,5.);
+#543=CIRCLE('',#1688,5.00000000000001);
+#544=CIRCLE('',#1691,5.00000000000001);
+#545=CIRCLE('',#1693,5.00000000000001);
+#546=CIRCLE('',#1695,5.00000000000001);
+#547=CIRCLE('',#1698,172.);
+#548=CIRCLE('',#1701,7.);
+#549=CIRCLE('',#1703,7.);
+#550=CIRCLE('',#1705,172.);
+#551=CIRCLE('',#1706,7.);
+#552=CIRCLE('',#1707,7.);
+#553=CIRCLE('',#1708,178.000000000002);
+#554=B_SPLINE_CURVE_WITH_KNOTS('',3,(#2226,#2227,#2228,#2229,#2230,#2231,
+#2232,#2233,#2234,#2235,#2236,#2237),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,4),
+(-0.68287522107553,-0.638467375111075,-0.529788063772799,-0.419356621472101,
+-0.304600118652942,-0.267223536945857),.UNSPECIFIED.);
+#555=B_SPLINE_CURVE_WITH_KNOTS('',3,(#2240,#2241,#2242,#2243,#2244,#2245),
+ .UNSPECIFIED.,.F.,.F.,(4,2,4),(-0.267223536945857,-0.188007615508465,-0.182445901244708),
+ .UNSPECIFIED.);
+#556=B_SPLINE_CURVE_WITH_KNOTS('',3,(#2255,#2256,#2257,#2258,#2259,#2260,
+#2261,#2262,#2263,#2264,#2265,#2266,#2267,#2268,#2269,#2270),
+ .UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,2,2,4),(-0.850976981863725,-0.76977451275866,
+-0.677726469158597,-0.624316361476475,-0.575869631821313,-0.510322423720033,
+-0.399283032104886,-0.373493825663556),.UNSPECIFIED.);
+#557=B_SPLINE_CURVE_WITH_KNOTS('',3,(#2283,#2284,#2285,#2286,#2287,#2288,
+#2289,#2290,#2291,#2292,#2293,#2294,#2295,#2296,#2297,#2298),
+ .UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,2,2,4),(-0.850976981858374,-0.769774512753926,
+-0.677726469154562,-0.624316361472872,-0.575869631818105,-0.510322423717342,
+-0.39928303210307,-0.373493825661946),.UNSPECIFIED.);
+#558=B_SPLINE_CURVE_WITH_KNOTS('',3,(#2311,#2312,#2313,#2314,#2315,#2316,
+#2317,#2318,#2319,#2320,#2321,#2322),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,4),
+(-0.689395441395202,-0.626772204335979,-0.519116646438061,-0.408145913852234,
+-0.293687321637465,-0.19286355592883),.UNSPECIFIED.);
+#559=VERTEX_POINT('',#2224);
+#560=VERTEX_POINT('',#2225);
+#561=VERTEX_POINT('',#2238);
+#562=VERTEX_POINT('',#2246);
+#563=VERTEX_POINT('',#2250);
+#564=VERTEX_POINT('',#2253);
+#565=VERTEX_POINT('',#2254);
+#566=VERTEX_POINT('',#2271);
+#567=VERTEX_POINT('',#2273);
+#568=VERTEX_POINT('',#2278);
+#569=VERTEX_POINT('',#2281);
+#570=VERTEX_POINT('',#2282);
+#571=VERTEX_POINT('',#2299);
+#572=VERTEX_POINT('',#2301);
+#573=VERTEX_POINT('',#2306);
+#574=VERTEX_POINT('',#2309);
+#575=VERTEX_POINT('',#2310);
+#576=VERTEX_POINT('',#2323);
+#577=VERTEX_POINT('',#2325);
+#578=VERTEX_POINT('',#2330);
+#579=VERTEX_POINT('',#2333);
+#580=VERTEX_POINT('',#2335);
+#581=VERTEX_POINT('',#2337);
+#582=VERTEX_POINT('',#2339);
+#583=VERTEX_POINT('',#2341);
+#584=VERTEX_POINT('',#2343);
+#585=VERTEX_POINT('',#2345);
+#586=VERTEX_POINT('',#2347);
+#587=VERTEX_POINT('',#2350);
+#588=VERTEX_POINT('',#2352);
+#589=VERTEX_POINT('',#2355);
+#590=VERTEX_POINT('',#2357);
+#591=VERTEX_POINT('',#2360);
+#592=VERTEX_POINT('',#2362);
+#593=VERTEX_POINT('',#2366);
+#594=VERTEX_POINT('',#2367);
+#595=VERTEX_POINT('',#2369);
+#596=VERTEX_POINT('',#2371);
+#597=VERTEX_POINT('',#2375);
+#598=VERTEX_POINT('',#2377);
+#599=VERTEX_POINT('',#2381);
+#600=VERTEX_POINT('',#2382);
+#601=VERTEX_POINT('',#2384);
+#602=VERTEX_POINT('',#2386);
+#603=VERTEX_POINT('',#2393);
+#604=VERTEX_POINT('',#2394);
+#605=VERTEX_POINT('',#2396);
+#606=VERTEX_POINT('',#2398);
+#607=VERTEX_POINT('',#2405);
+#608=VERTEX_POINT('',#2407);
+#609=VERTEX_POINT('',#2414);
+#610=VERTEX_POINT('',#2416);
+#611=VERTEX_POINT('',#2420);
+#612=VERTEX_POINT('',#2421);
+#613=VERTEX_POINT('',#2426);
+#614=VERTEX_POINT('',#2428);
+#615=VERTEX_POINT('',#2432);
+#616=VERTEX_POINT('',#2433);
+#617=VERTEX_POINT('',#2438);
+#618=VERTEX_POINT('',#2440);
+#619=VERTEX_POINT('',#2444);
+#620=VERTEX_POINT('',#2445);
+#621=VERTEX_POINT('',#2452);
+#622=VERTEX_POINT('',#2454);
+#623=VERTEX_POINT('',#2458);
+#624=VERTEX_POINT('',#2459);
+#625=VERTEX_POINT('',#2464);
+#626=VERTEX_POINT('',#2468);
+#627=VERTEX_POINT('',#2472);
+#628=VERTEX_POINT('',#2476);
+#629=VERTEX_POINT('',#2480);
+#630=VERTEX_POINT('',#2484);
+#631=VERTEX_POINT('',#2488);
+#632=VERTEX_POINT('',#2492);
+#633=VERTEX_POINT('',#2502);
+#634=VERTEX_POINT('',#2506);
+#635=VERTEX_POINT('',#2508);
+#636=VERTEX_POINT('',#2510);
+#637=VERTEX_POINT('',#2512);
+#638=VERTEX_POINT('',#2514);
+#639=VERTEX_POINT('',#2518);
+#640=VERTEX_POINT('',#2522);
+#641=VERTEX_POINT('',#2524);
+#642=VERTEX_POINT('',#2526);
+#643=VERTEX_POINT('',#2528);
+#644=VERTEX_POINT('',#2530);
+#645=VERTEX_POINT('',#2534);
+#646=VERTEX_POINT('',#2538);
+#647=VERTEX_POINT('',#2540);
+#648=VERTEX_POINT('',#2542);
+#649=VERTEX_POINT('',#2544);
+#650=VERTEX_POINT('',#2546);
+#651=VERTEX_POINT('',#2550);
+#652=VERTEX_POINT('',#2554);
+#653=VERTEX_POINT('',#2556);
+#654=VERTEX_POINT('',#2558);
+#655=VERTEX_POINT('',#2560);
+#656=VERTEX_POINT('',#2562);
+#657=VERTEX_POINT('',#2568);
+#658=VERTEX_POINT('',#2569);
+#659=VERTEX_POINT('',#2571);
+#660=VERTEX_POINT('',#2573);
+#661=VERTEX_POINT('',#2577);
+#662=VERTEX_POINT('',#2578);
+#663=VERTEX_POINT('',#2580);
+#664=VERTEX_POINT('',#2582);
+#665=VERTEX_POINT('',#2596);
+#666=VERTEX_POINT('',#2598);
+#667=VERTEX_POINT('',#2600);
+#668=VERTEX_POINT('',#2602);
+#669=VERTEX_POINT('',#2604);
+#670=VERTEX_POINT('',#2606);
+#671=VERTEX_POINT('',#2608);
+#672=VERTEX_POINT('',#2610);
+#673=VERTEX_POINT('',#2612);
+#674=VERTEX_POINT('',#2614);
+#675=VERTEX_POINT('',#2616);
+#676=VERTEX_POINT('',#2618);
+#677=VERTEX_POINT('',#2620);
+#678=VERTEX_POINT('',#2622);
+#679=VERTEX_POINT('',#2624);
+#680=VERTEX_POINT('',#2626);
+#681=VERTEX_POINT('',#2630);
+#682=VERTEX_POINT('',#2632);
+#683=VERTEX_POINT('',#2634);
+#684=VERTEX_POINT('',#2636);
+#685=VERTEX_POINT('',#2639);
+#686=VERTEX_POINT('',#2641);
+#687=VERTEX_POINT('',#2656);
+#688=VERTEX_POINT('',#2658);
+#689=VERTEX_POINT('',#2664);
+#690=VERTEX_POINT('',#2666);
+#691=VERTEX_POINT('',#2674);
+#692=VERTEX_POINT('',#2676);
+#693=VERTEX_POINT('',#2682);
+#694=VERTEX_POINT('',#2684);
+#695=VERTEX_POINT('',#2689);
+#696=VERTEX_POINT('',#2693);
+#697=VERTEX_POINT('',#2697);
+#698=VERTEX_POINT('',#2701);
+#699=VERTEX_POINT('',#2706);
+#700=VERTEX_POINT('',#2710);
+#701=EDGE_CURVE('',#559,#560,#554,.T.);
+#702=EDGE_CURVE('',#561,#559,#434,.T.);
+#703=EDGE_CURVE('',#560,#561,#555,.T.);
+#704=EDGE_CURVE('',#560,#562,#240,.T.);
+#705=EDGE_CURVE('',#562,#562,#435,.T.);
+#706=EDGE_CURVE('',#563,#563,#436,.T.);
+#707=EDGE_CURVE('',#564,#565,#556,.T.);
+#708=EDGE_CURVE('',#566,#564,#437,.T.);
+#709=EDGE_CURVE('',#566,#567,#241,.T.);
+#710=EDGE_CURVE('',#567,#567,#438,.T.);
+#711=EDGE_CURVE('',#565,#566,#439,.T.);
+#712=EDGE_CURVE('',#568,#568,#440,.T.);
+#713=EDGE_CURVE('',#569,#570,#557,.T.);
+#714=EDGE_CURVE('',#571,#569,#441,.T.);
+#715=EDGE_CURVE('',#571,#572,#242,.T.);
+#716=EDGE_CURVE('',#572,#572,#442,.T.);
+#717=EDGE_CURVE('',#570,#571,#443,.T.);
+#718=EDGE_CURVE('',#573,#573,#444,.T.);
+#719=EDGE_CURVE('',#574,#575,#558,.T.);
+#720=EDGE_CURVE('',#576,#574,#445,.T.);
+#721=EDGE_CURVE('',#576,#577,#243,.T.);
+#722=EDGE_CURVE('',#577,#577,#446,.T.);
+#723=EDGE_CURVE('',#575,#576,#447,.T.);
+#724=EDGE_CURVE('',#578,#578,#448,.T.);
+#725=EDGE_CURVE('',#579,#559,#449,.T.);
+#726=EDGE_CURVE('',#580,#579,#450,.T.);
+#727=EDGE_CURVE('',#581,#580,#451,.T.);
+#728=EDGE_CURVE('',#582,#581,#244,.T.);
+#729=EDGE_CURVE('',#583,#582,#245,.T.);
+#730=EDGE_CURVE('',#584,#583,#246,.T.);
+#731=EDGE_CURVE('',#585,#584,#452,.T.);
+#732=EDGE_CURVE('',#586,#585,#453,.T.);
+#733=EDGE_CURVE('',#575,#586,#454,.T.);
+#734=EDGE_CURVE('',#587,#574,#455,.T.);
+#735=EDGE_CURVE('',#588,#587,#247,.T.);
+#736=EDGE_CURVE('',#565,#588,#456,.T.);
+#737=EDGE_CURVE('',#589,#564,#457,.T.);
+#738=EDGE_CURVE('',#590,#589,#458,.T.);
+#739=EDGE_CURVE('',#570,#590,#459,.T.);
+#740=EDGE_CURVE('',#591,#569,#460,.T.);
+#741=EDGE_CURVE('',#592,#591,#248,.T.);
+#742=EDGE_CURVE('',#561,#592,#461,.T.);
+#743=EDGE_CURVE('',#593,#594,#462,.T.);
+#744=EDGE_CURVE('',#594,#595,#249,.T.);
+#745=EDGE_CURVE('',#595,#596,#463,.T.);
+#746=EDGE_CURVE('',#596,#593,#250,.T.);
+#747=EDGE_CURVE('',#597,#594,#251,.T.);
+#748=EDGE_CURVE('',#598,#597,#252,.T.);
+#749=EDGE_CURVE('',#595,#598,#253,.T.);
+#750=EDGE_CURVE('',#599,#600,#464,.T.);
+#751=EDGE_CURVE('',#600,#601,#254,.T.);
+#752=EDGE_CURVE('',#601,#602,#465,.T.);
+#753=EDGE_CURVE('',#602,#599,#255,.T.);
+#754=EDGE_CURVE('',#601,#596,#256,.T.);
+#755=EDGE_CURVE('',#593,#600,#257,.T.);
+#756=EDGE_CURVE('',#603,#604,#466,.T.);
+#757=EDGE_CURVE('',#604,#605,#258,.T.);
+#758=EDGE_CURVE('',#605,#606,#467,.T.);
+#759=EDGE_CURVE('',#606,#603,#259,.T.);
+#760=EDGE_CURVE('',#605,#602,#260,.T.);
+#761=EDGE_CURVE('',#599,#604,#261,.T.);
+#762=EDGE_CURVE('',#597,#607,#468,.T.);
+#763=EDGE_CURVE('',#607,#608,#262,.T.);
+#764=EDGE_CURVE('',#608,#598,#469,.T.);
+#765=EDGE_CURVE('',#608,#606,#263,.T.);
+#766=EDGE_CURVE('',#603,#607,#264,.T.);
+#767=EDGE_CURVE('',#609,#582,#470,.F.);
+#768=EDGE_CURVE('',#610,#609,#471,.F.);
+#769=EDGE_CURVE('',#582,#610,#472,.F.);
+#770=EDGE_CURVE('',#611,#612,#473,.T.);
+#771=EDGE_CURVE('',#612,#610,#265,.T.);
+#772=EDGE_CURVE('',#609,#611,#266,.T.);
+#773=EDGE_CURVE('',#613,#583,#474,.F.);
+#774=EDGE_CURVE('',#614,#613,#475,.F.);
+#775=EDGE_CURVE('',#583,#614,#476,.F.);
+#776=EDGE_CURVE('',#615,#616,#477,.T.);
+#777=EDGE_CURVE('',#616,#614,#267,.T.);
+#778=EDGE_CURVE('',#613,#615,#268,.T.);
+#779=EDGE_CURVE('',#617,#580,#478,.T.);
+#780=EDGE_CURVE('',#618,#617,#479,.F.);
+#781=EDGE_CURVE('',#581,#618,#480,.T.);
+#782=EDGE_CURVE('',#619,#620,#481,.T.);
+#783=EDGE_CURVE('',#620,#618,#269,.T.);
+#784=EDGE_CURVE('',#617,#619,#270,.T.);
+#785=EDGE_CURVE('',#618,#609,#271,.T.);
+#786=EDGE_CURVE('',#621,#584,#482,.T.);
+#787=EDGE_CURVE('',#622,#621,#483,.F.);
+#788=EDGE_CURVE('',#585,#622,#484,.T.);
+#789=EDGE_CURVE('',#623,#624,#485,.T.);
+#790=EDGE_CURVE('',#624,#622,#272,.T.);
+#791=EDGE_CURVE('',#621,#623,#273,.T.);
+#792=EDGE_CURVE('',#625,#586,#486,.T.);
+#793=EDGE_CURVE('',#622,#625,#487,.T.);
+#794=EDGE_CURVE('',#625,#626,#488,.T.);
+#795=EDGE_CURVE('',#626,#587,#489,.T.);
+#796=EDGE_CURVE('',#627,#588,#490,.T.);
+#797=EDGE_CURVE('',#626,#627,#274,.T.);
+#798=EDGE_CURVE('',#627,#628,#491,.T.);
+#799=EDGE_CURVE('',#628,#589,#492,.T.);
+#800=EDGE_CURVE('',#629,#590,#493,.T.);
+#801=EDGE_CURVE('',#628,#629,#494,.T.);
+#802=EDGE_CURVE('',#629,#630,#495,.T.);
+#803=EDGE_CURVE('',#630,#591,#496,.T.);
+#804=EDGE_CURVE('',#631,#592,#497,.T.);
+#805=EDGE_CURVE('',#630,#631,#275,.T.);
+#806=EDGE_CURVE('',#631,#632,#498,.T.);
+#807=EDGE_CURVE('',#632,#579,#499,.T.);
+#808=EDGE_CURVE('',#632,#617,#500,.T.);
+#809=EDGE_CURVE('',#614,#621,#276,.T.);
+#810=EDGE_CURVE('',#610,#613,#277,.T.);
+#811=EDGE_CURVE('',#633,#632,#278,.T.);
+#812=EDGE_CURVE('',#633,#619,#501,.T.);
+#813=EDGE_CURVE('',#634,#631,#279,.T.);
+#814=EDGE_CURVE('',#634,#635,#502,.T.);
+#815=EDGE_CURVE('',#635,#636,#280,.T.);
+#816=EDGE_CURVE('',#636,#637,#503,.T.);
+#817=EDGE_CURVE('',#637,#638,#281,.T.);
+#818=EDGE_CURVE('',#638,#633,#504,.T.);
+#819=EDGE_CURVE('',#639,#630,#282,.T.);
+#820=EDGE_CURVE('',#639,#634,#283,.T.);
+#821=EDGE_CURVE('',#640,#629,#284,.T.);
+#822=EDGE_CURVE('',#640,#641,#505,.T.);
+#823=EDGE_CURVE('',#641,#642,#285,.T.);
+#824=EDGE_CURVE('',#642,#643,#506,.T.);
+#825=EDGE_CURVE('',#643,#644,#286,.T.);
+#826=EDGE_CURVE('',#644,#639,#507,.T.);
+#827=EDGE_CURVE('',#645,#628,#287,.T.);
+#828=EDGE_CURVE('',#645,#640,#508,.T.);
+#829=EDGE_CURVE('',#646,#627,#288,.T.);
+#830=EDGE_CURVE('',#646,#647,#509,.T.);
+#831=EDGE_CURVE('',#647,#648,#289,.T.);
+#832=EDGE_CURVE('',#648,#649,#510,.T.);
+#833=EDGE_CURVE('',#649,#650,#290,.T.);
+#834=EDGE_CURVE('',#650,#645,#511,.T.);
+#835=EDGE_CURVE('',#651,#626,#291,.T.);
+#836=EDGE_CURVE('',#651,#646,#292,.T.);
+#837=EDGE_CURVE('',#652,#625,#293,.T.);
+#838=EDGE_CURVE('',#652,#653,#512,.T.);
+#839=EDGE_CURVE('',#653,#654,#294,.T.);
+#840=EDGE_CURVE('',#654,#655,#513,.T.);
+#841=EDGE_CURVE('',#655,#656,#295,.T.);
+#842=EDGE_CURVE('',#656,#651,#514,.T.);
+#843=EDGE_CURVE('',#624,#652,#515,.T.);
+#844=EDGE_CURVE('',#657,#658,#296,.T.);
+#845=EDGE_CURVE('',#659,#657,#516,.T.);
+#846=EDGE_CURVE('',#660,#659,#297,.T.);
+#847=EDGE_CURVE('',#658,#660,#517,.T.);
+#848=EDGE_CURVE('',#661,#662,#298,.T.);
+#849=EDGE_CURVE('',#663,#661,#518,.T.);
+#850=EDGE_CURVE('',#664,#663,#299,.T.);
+#851=EDGE_CURVE('',#662,#664,#519,.T.);
+#852=EDGE_CURVE('',#661,#659,#300,.T.);
+#853=EDGE_CURVE('',#662,#660,#301,.T.);
+#854=EDGE_CURVE('',#620,#611,#302,.T.);
+#855=EDGE_CURVE('',#638,#635,#520,.T.);
+#856=EDGE_CURVE('',#644,#641,#521,.T.);
+#857=EDGE_CURVE('',#650,#647,#522,.T.);
+#858=EDGE_CURVE('',#656,#653,#523,.T.);
+#859=EDGE_CURVE('',#616,#623,#303,.T.);
+#860=EDGE_CURVE('',#657,#615,#304,.T.);
+#861=EDGE_CURVE('',#658,#665,#305,.T.);
+#862=EDGE_CURVE('',#665,#666,#306,.T.);
+#863=EDGE_CURVE('',#666,#667,#524,.T.);
+#864=EDGE_CURVE('',#667,#668,#525,.T.);
+#865=EDGE_CURVE('',#668,#669,#307,.T.);
+#866=EDGE_CURVE('',#669,#670,#526,.T.);
+#867=EDGE_CURVE('',#670,#671,#527,.T.);
+#868=EDGE_CURVE('',#671,#672,#528,.T.);
+#869=EDGE_CURVE('',#672,#673,#529,.T.);
+#870=EDGE_CURVE('',#673,#674,#530,.T.);
+#871=EDGE_CURVE('',#674,#675,#531,.T.);
+#872=EDGE_CURVE('',#675,#676,#532,.T.);
+#873=EDGE_CURVE('',#676,#677,#308,.T.);
+#874=EDGE_CURVE('',#677,#678,#533,.T.);
+#875=EDGE_CURVE('',#678,#679,#534,.T.);
+#876=EDGE_CURVE('',#679,#680,#309,.T.);
+#877=EDGE_CURVE('',#680,#664,#310,.T.);
+#878=EDGE_CURVE('',#612,#663,#311,.T.);
+#879=EDGE_CURVE('',#681,#681,#535,.T.);
+#880=EDGE_CURVE('',#682,#682,#536,.T.);
+#881=EDGE_CURVE('',#683,#683,#537,.T.);
+#882=EDGE_CURVE('',#684,#684,#538,.T.);
+#883=EDGE_CURVE('',#680,#685,#312,.F.);
+#884=EDGE_CURVE('',#685,#686,#313,.F.);
+#885=EDGE_CURVE('',#665,#686,#314,.F.);
+#886=EDGE_CURVE('',#684,#578,#315,.T.);
+#887=EDGE_CURVE('',#683,#563,#316,.T.);
+#888=EDGE_CURVE('',#682,#568,#317,.T.);
+#889=EDGE_CURVE('',#681,#573,#318,.T.);
+#890=EDGE_CURVE('',#655,#654,#539,.T.);
+#891=EDGE_CURVE('',#668,#687,#319,.T.);
+#892=EDGE_CURVE('',#688,#667,#320,.T.);
+#893=EDGE_CURVE('',#687,#688,#540,.T.);
+#894=EDGE_CURVE('',#637,#636,#541,.T.);
+#895=EDGE_CURVE('',#678,#689,#321,.T.);
+#896=EDGE_CURVE('',#690,#677,#322,.T.);
+#897=EDGE_CURVE('',#689,#690,#542,.T.);
+#898=EDGE_CURVE('',#649,#648,#543,.T.);
+#899=EDGE_CURVE('',#691,#670,#323,.T.);
+#900=EDGE_CURVE('',#692,#691,#544,.T.);
+#901=EDGE_CURVE('',#671,#692,#324,.T.);
+#902=EDGE_CURVE('',#643,#642,#545,.T.);
+#903=EDGE_CURVE('',#675,#693,#325,.T.);
+#904=EDGE_CURVE('',#694,#674,#326,.T.);
+#905=EDGE_CURVE('',#693,#694,#546,.T.);
+#906=EDGE_CURVE('',#666,#695,#327,.T.);
+#907=EDGE_CURVE('',#695,#688,#547,.F.);
+#908=EDGE_CURVE('',#676,#696,#328,.T.);
+#909=EDGE_CURVE('',#696,#690,#329,.F.);
+#910=EDGE_CURVE('',#692,#697,#548,.F.);
+#911=EDGE_CURVE('',#672,#697,#330,.T.);
+#912=EDGE_CURVE('',#669,#698,#331,.T.);
+#913=EDGE_CURVE('',#698,#691,#549,.F.);
+#914=EDGE_CURVE('',#686,#695,#332,.F.);
+#915=EDGE_CURVE('',#699,#685,#333,.F.);
+#916=EDGE_CURVE('',#689,#699,#550,.F.);
+#917=EDGE_CURVE('',#693,#696,#551,.F.);
+#918=EDGE_CURVE('',#700,#694,#552,.F.);
+#919=EDGE_CURVE('',#697,#700,#553,.F.);
+#920=EDGE_CURVE('',#687,#698,#334,.F.);
+#921=EDGE_CURVE('',#673,#700,#335,.T.);
+#922=EDGE_CURVE('',#679,#699,#336,.T.);
+#923=ORIENTED_EDGE('',*,*,#701,.F.);
+#924=ORIENTED_EDGE('',*,*,#702,.F.);
+#925=ORIENTED_EDGE('',*,*,#703,.F.);
+#926=ORIENTED_EDGE('',*,*,#704,.T.);
+#927=ORIENTED_EDGE('',*,*,#705,.T.);
+#928=ORIENTED_EDGE('',*,*,#704,.F.);
+#929=ORIENTED_EDGE('',*,*,#705,.F.);
+#930=ORIENTED_EDGE('',*,*,#706,.F.);
+#931=ORIENTED_EDGE('',*,*,#707,.F.);
+#932=ORIENTED_EDGE('',*,*,#708,.F.);
+#933=ORIENTED_EDGE('',*,*,#709,.T.);
+#934=ORIENTED_EDGE('',*,*,#710,.T.);
+#935=ORIENTED_EDGE('',*,*,#709,.F.);
+#936=ORIENTED_EDGE('',*,*,#711,.F.);
+#937=ORIENTED_EDGE('',*,*,#710,.F.);
+#938=ORIENTED_EDGE('',*,*,#712,.F.);
+#939=ORIENTED_EDGE('',*,*,#713,.F.);
+#940=ORIENTED_EDGE('',*,*,#714,.F.);
+#941=ORIENTED_EDGE('',*,*,#715,.T.);
+#942=ORIENTED_EDGE('',*,*,#716,.T.);
+#943=ORIENTED_EDGE('',*,*,#715,.F.);
+#944=ORIENTED_EDGE('',*,*,#717,.F.);
+#945=ORIENTED_EDGE('',*,*,#716,.F.);
+#946=ORIENTED_EDGE('',*,*,#718,.F.);
+#947=ORIENTED_EDGE('',*,*,#719,.F.);
+#948=ORIENTED_EDGE('',*,*,#720,.F.);
+#949=ORIENTED_EDGE('',*,*,#721,.T.);
+#950=ORIENTED_EDGE('',*,*,#722,.T.);
+#951=ORIENTED_EDGE('',*,*,#721,.F.);
+#952=ORIENTED_EDGE('',*,*,#723,.F.);
+#953=ORIENTED_EDGE('',*,*,#722,.F.);
+#954=ORIENTED_EDGE('',*,*,#724,.F.);
+#955=ORIENTED_EDGE('',*,*,#702,.T.);
+#956=ORIENTED_EDGE('',*,*,#725,.F.);
+#957=ORIENTED_EDGE('',*,*,#726,.F.);
+#958=ORIENTED_EDGE('',*,*,#727,.F.);
+#959=ORIENTED_EDGE('',*,*,#728,.F.);
+#960=ORIENTED_EDGE('',*,*,#729,.F.);
+#961=ORIENTED_EDGE('',*,*,#730,.F.);
+#962=ORIENTED_EDGE('',*,*,#731,.F.);
+#963=ORIENTED_EDGE('',*,*,#732,.F.);
+#964=ORIENTED_EDGE('',*,*,#733,.F.);
+#965=ORIENTED_EDGE('',*,*,#723,.T.);
+#966=ORIENTED_EDGE('',*,*,#720,.T.);
+#967=ORIENTED_EDGE('',*,*,#734,.F.);
+#968=ORIENTED_EDGE('',*,*,#735,.F.);
+#969=ORIENTED_EDGE('',*,*,#736,.F.);
+#970=ORIENTED_EDGE('',*,*,#711,.T.);
+#971=ORIENTED_EDGE('',*,*,#708,.T.);
+#972=ORIENTED_EDGE('',*,*,#737,.F.);
+#973=ORIENTED_EDGE('',*,*,#738,.F.);
+#974=ORIENTED_EDGE('',*,*,#739,.F.);
+#975=ORIENTED_EDGE('',*,*,#717,.T.);
+#976=ORIENTED_EDGE('',*,*,#714,.T.);
+#977=ORIENTED_EDGE('',*,*,#740,.F.);
+#978=ORIENTED_EDGE('',*,*,#741,.F.);
+#979=ORIENTED_EDGE('',*,*,#742,.F.);
+#980=ORIENTED_EDGE('',*,*,#743,.T.);
+#981=ORIENTED_EDGE('',*,*,#744,.T.);
+#982=ORIENTED_EDGE('',*,*,#745,.T.);
+#983=ORIENTED_EDGE('',*,*,#746,.T.);
+#984=ORIENTED_EDGE('',*,*,#744,.F.);
+#985=ORIENTED_EDGE('',*,*,#747,.F.);
+#986=ORIENTED_EDGE('',*,*,#748,.F.);
+#987=ORIENTED_EDGE('',*,*,#749,.F.);
+#988=ORIENTED_EDGE('',*,*,#750,.T.);
+#989=ORIENTED_EDGE('',*,*,#751,.T.);
+#990=ORIENTED_EDGE('',*,*,#752,.T.);
+#991=ORIENTED_EDGE('',*,*,#753,.T.);
+#992=ORIENTED_EDGE('',*,*,#746,.F.);
+#993=ORIENTED_EDGE('',*,*,#754,.F.);
+#994=ORIENTED_EDGE('',*,*,#751,.F.);
+#995=ORIENTED_EDGE('',*,*,#755,.F.);
+#996=ORIENTED_EDGE('',*,*,#756,.T.);
+#997=ORIENTED_EDGE('',*,*,#757,.T.);
+#998=ORIENTED_EDGE('',*,*,#758,.T.);
+#999=ORIENTED_EDGE('',*,*,#759,.T.);
+#1000=ORIENTED_EDGE('',*,*,#753,.F.);
+#1001=ORIENTED_EDGE('',*,*,#760,.F.);
+#1002=ORIENTED_EDGE('',*,*,#757,.F.);
+#1003=ORIENTED_EDGE('',*,*,#761,.F.);
+#1004=ORIENTED_EDGE('',*,*,#762,.T.);
+#1005=ORIENTED_EDGE('',*,*,#763,.T.);
+#1006=ORIENTED_EDGE('',*,*,#764,.T.);
+#1007=ORIENTED_EDGE('',*,*,#748,.T.);
+#1008=ORIENTED_EDGE('',*,*,#759,.F.);
+#1009=ORIENTED_EDGE('',*,*,#765,.F.);
+#1010=ORIENTED_EDGE('',*,*,#763,.F.);
+#1011=ORIENTED_EDGE('',*,*,#766,.F.);
+#1012=ORIENTED_EDGE('',*,*,#767,.F.);
+#1013=ORIENTED_EDGE('',*,*,#768,.F.);
+#1014=ORIENTED_EDGE('',*,*,#769,.F.);
+#1015=ORIENTED_EDGE('',*,*,#770,.T.);
+#1016=ORIENTED_EDGE('',*,*,#771,.T.);
+#1017=ORIENTED_EDGE('',*,*,#768,.T.);
+#1018=ORIENTED_EDGE('',*,*,#772,.T.);
+#1019=ORIENTED_EDGE('',*,*,#773,.F.);
+#1020=ORIENTED_EDGE('',*,*,#774,.F.);
+#1021=ORIENTED_EDGE('',*,*,#775,.F.);
+#1022=ORIENTED_EDGE('',*,*,#776,.T.);
+#1023=ORIENTED_EDGE('',*,*,#777,.T.);
+#1024=ORIENTED_EDGE('',*,*,#774,.T.);
+#1025=ORIENTED_EDGE('',*,*,#778,.T.);
+#1026=ORIENTED_EDGE('',*,*,#779,.F.);
+#1027=ORIENTED_EDGE('',*,*,#780,.F.);
+#1028=ORIENTED_EDGE('',*,*,#781,.F.);
+#1029=ORIENTED_EDGE('',*,*,#727,.T.);
+#1030=ORIENTED_EDGE('',*,*,#782,.T.);
+#1031=ORIENTED_EDGE('',*,*,#783,.T.);
+#1032=ORIENTED_EDGE('',*,*,#780,.T.);
+#1033=ORIENTED_EDGE('',*,*,#784,.T.);
+#1034=ORIENTED_EDGE('',*,*,#767,.T.);
+#1035=ORIENTED_EDGE('',*,*,#728,.T.);
+#1036=ORIENTED_EDGE('',*,*,#781,.T.);
+#1037=ORIENTED_EDGE('',*,*,#785,.T.);
+#1038=ORIENTED_EDGE('',*,*,#786,.F.);
+#1039=ORIENTED_EDGE('',*,*,#787,.F.);
+#1040=ORIENTED_EDGE('',*,*,#788,.F.);
+#1041=ORIENTED_EDGE('',*,*,#731,.T.);
+#1042=ORIENTED_EDGE('',*,*,#789,.T.);
+#1043=ORIENTED_EDGE('',*,*,#790,.T.);
+#1044=ORIENTED_EDGE('',*,*,#787,.T.);
+#1045=ORIENTED_EDGE('',*,*,#791,.T.);
+#1046=ORIENTED_EDGE('',*,*,#792,.T.);
+#1047=ORIENTED_EDGE('',*,*,#732,.T.);
+#1048=ORIENTED_EDGE('',*,*,#788,.T.);
+#1049=ORIENTED_EDGE('',*,*,#793,.T.);
+#1050=ORIENTED_EDGE('',*,*,#719,.T.);
+#1051=ORIENTED_EDGE('',*,*,#733,.T.);
+#1052=ORIENTED_EDGE('',*,*,#792,.F.);
+#1053=ORIENTED_EDGE('',*,*,#794,.T.);
+#1054=ORIENTED_EDGE('',*,*,#795,.T.);
+#1055=ORIENTED_EDGE('',*,*,#734,.T.);
+#1056=ORIENTED_EDGE('',*,*,#796,.T.);
+#1057=ORIENTED_EDGE('',*,*,#735,.T.);
+#1058=ORIENTED_EDGE('',*,*,#795,.F.);
+#1059=ORIENTED_EDGE('',*,*,#797,.T.);
+#1060=ORIENTED_EDGE('',*,*,#707,.T.);
+#1061=ORIENTED_EDGE('',*,*,#736,.T.);
+#1062=ORIENTED_EDGE('',*,*,#796,.F.);
+#1063=ORIENTED_EDGE('',*,*,#798,.T.);
+#1064=ORIENTED_EDGE('',*,*,#799,.T.);
+#1065=ORIENTED_EDGE('',*,*,#737,.T.);
+#1066=ORIENTED_EDGE('',*,*,#800,.T.);
+#1067=ORIENTED_EDGE('',*,*,#738,.T.);
+#1068=ORIENTED_EDGE('',*,*,#799,.F.);
+#1069=ORIENTED_EDGE('',*,*,#801,.T.);
+#1070=ORIENTED_EDGE('',*,*,#713,.T.);
+#1071=ORIENTED_EDGE('',*,*,#739,.T.);
+#1072=ORIENTED_EDGE('',*,*,#800,.F.);
+#1073=ORIENTED_EDGE('',*,*,#802,.T.);
+#1074=ORIENTED_EDGE('',*,*,#803,.T.);
+#1075=ORIENTED_EDGE('',*,*,#740,.T.);
+#1076=ORIENTED_EDGE('',*,*,#804,.T.);
+#1077=ORIENTED_EDGE('',*,*,#741,.T.);
+#1078=ORIENTED_EDGE('',*,*,#803,.F.);
+#1079=ORIENTED_EDGE('',*,*,#805,.T.);
+#1080=ORIENTED_EDGE('',*,*,#701,.T.);
+#1081=ORIENTED_EDGE('',*,*,#703,.T.);
+#1082=ORIENTED_EDGE('',*,*,#742,.T.);
+#1083=ORIENTED_EDGE('',*,*,#804,.F.);
+#1084=ORIENTED_EDGE('',*,*,#806,.T.);
+#1085=ORIENTED_EDGE('',*,*,#807,.T.);
+#1086=ORIENTED_EDGE('',*,*,#725,.T.);
+#1087=ORIENTED_EDGE('',*,*,#779,.T.);
+#1088=ORIENTED_EDGE('',*,*,#726,.T.);
+#1089=ORIENTED_EDGE('',*,*,#807,.F.);
+#1090=ORIENTED_EDGE('',*,*,#808,.T.);
+#1091=ORIENTED_EDGE('',*,*,#786,.T.);
+#1092=ORIENTED_EDGE('',*,*,#730,.T.);
+#1093=ORIENTED_EDGE('',*,*,#775,.T.);
+#1094=ORIENTED_EDGE('',*,*,#809,.T.);
+#1095=ORIENTED_EDGE('',*,*,#773,.T.);
+#1096=ORIENTED_EDGE('',*,*,#729,.T.);
+#1097=ORIENTED_EDGE('',*,*,#769,.T.);
+#1098=ORIENTED_EDGE('',*,*,#810,.T.);
+#1099=ORIENTED_EDGE('',*,*,#784,.F.);
+#1100=ORIENTED_EDGE('',*,*,#808,.F.);
+#1101=ORIENTED_EDGE('',*,*,#811,.F.);
+#1102=ORIENTED_EDGE('',*,*,#812,.T.);
+#1103=ORIENTED_EDGE('',*,*,#806,.F.);
+#1104=ORIENTED_EDGE('',*,*,#813,.F.);
+#1105=ORIENTED_EDGE('',*,*,#814,.T.);
+#1106=ORIENTED_EDGE('',*,*,#815,.T.);
+#1107=ORIENTED_EDGE('',*,*,#816,.T.);
+#1108=ORIENTED_EDGE('',*,*,#817,.T.);
+#1109=ORIENTED_EDGE('',*,*,#818,.T.);
+#1110=ORIENTED_EDGE('',*,*,#811,.T.);
+#1111=ORIENTED_EDGE('',*,*,#805,.F.);
+#1112=ORIENTED_EDGE('',*,*,#819,.F.);
+#1113=ORIENTED_EDGE('',*,*,#820,.T.);
+#1114=ORIENTED_EDGE('',*,*,#813,.T.);
+#1115=ORIENTED_EDGE('',*,*,#802,.F.);
+#1116=ORIENTED_EDGE('',*,*,#821,.F.);
+#1117=ORIENTED_EDGE('',*,*,#822,.T.);
+#1118=ORIENTED_EDGE('',*,*,#823,.T.);
+#1119=ORIENTED_EDGE('',*,*,#824,.T.);
+#1120=ORIENTED_EDGE('',*,*,#825,.T.);
+#1121=ORIENTED_EDGE('',*,*,#826,.T.);
+#1122=ORIENTED_EDGE('',*,*,#819,.T.);
+#1123=ORIENTED_EDGE('',*,*,#801,.F.);
+#1124=ORIENTED_EDGE('',*,*,#827,.F.);
+#1125=ORIENTED_EDGE('',*,*,#828,.T.);
+#1126=ORIENTED_EDGE('',*,*,#821,.T.);
+#1127=ORIENTED_EDGE('',*,*,#798,.F.);
+#1128=ORIENTED_EDGE('',*,*,#829,.F.);
+#1129=ORIENTED_EDGE('',*,*,#830,.T.);
+#1130=ORIENTED_EDGE('',*,*,#831,.T.);
+#1131=ORIENTED_EDGE('',*,*,#832,.T.);
+#1132=ORIENTED_EDGE('',*,*,#833,.T.);
+#1133=ORIENTED_EDGE('',*,*,#834,.T.);
+#1134=ORIENTED_EDGE('',*,*,#827,.T.);
+#1135=ORIENTED_EDGE('',*,*,#797,.F.);
+#1136=ORIENTED_EDGE('',*,*,#835,.F.);
+#1137=ORIENTED_EDGE('',*,*,#836,.T.);
+#1138=ORIENTED_EDGE('',*,*,#829,.T.);
+#1139=ORIENTED_EDGE('',*,*,#747,.T.);
+#1140=ORIENTED_EDGE('',*,*,#743,.F.);
+#1141=ORIENTED_EDGE('',*,*,#755,.T.);
+#1142=ORIENTED_EDGE('',*,*,#750,.F.);
+#1143=ORIENTED_EDGE('',*,*,#761,.T.);
+#1144=ORIENTED_EDGE('',*,*,#756,.F.);
+#1145=ORIENTED_EDGE('',*,*,#766,.T.);
+#1146=ORIENTED_EDGE('',*,*,#762,.F.);
+#1147=ORIENTED_EDGE('',*,*,#794,.F.);
+#1148=ORIENTED_EDGE('',*,*,#837,.F.);
+#1149=ORIENTED_EDGE('',*,*,#838,.T.);
+#1150=ORIENTED_EDGE('',*,*,#839,.T.);
+#1151=ORIENTED_EDGE('',*,*,#840,.T.);
+#1152=ORIENTED_EDGE('',*,*,#841,.T.);
+#1153=ORIENTED_EDGE('',*,*,#842,.T.);
+#1154=ORIENTED_EDGE('',*,*,#835,.T.);
+#1155=ORIENTED_EDGE('',*,*,#793,.F.);
+#1156=ORIENTED_EDGE('',*,*,#790,.F.);
+#1157=ORIENTED_EDGE('',*,*,#843,.T.);
+#1158=ORIENTED_EDGE('',*,*,#837,.T.);
+#1159=ORIENTED_EDGE('',*,*,#844,.F.);
+#1160=ORIENTED_EDGE('',*,*,#845,.F.);
+#1161=ORIENTED_EDGE('',*,*,#846,.F.);
+#1162=ORIENTED_EDGE('',*,*,#847,.F.);
+#1163=ORIENTED_EDGE('',*,*,#848,.F.);
+#1164=ORIENTED_EDGE('',*,*,#849,.F.);
+#1165=ORIENTED_EDGE('',*,*,#850,.F.);
+#1166=ORIENTED_EDGE('',*,*,#851,.F.);
+#1167=ORIENTED_EDGE('',*,*,#846,.T.);
+#1168=ORIENTED_EDGE('',*,*,#852,.F.);
+#1169=ORIENTED_EDGE('',*,*,#848,.T.);
+#1170=ORIENTED_EDGE('',*,*,#853,.T.);
+#1171=ORIENTED_EDGE('',*,*,#770,.F.);
+#1172=ORIENTED_EDGE('',*,*,#854,.F.);
+#1173=ORIENTED_EDGE('',*,*,#782,.F.);
+#1174=ORIENTED_EDGE('',*,*,#812,.F.);
+#1175=ORIENTED_EDGE('',*,*,#818,.F.);
+#1176=ORIENTED_EDGE('',*,*,#855,.T.);
+#1177=ORIENTED_EDGE('',*,*,#814,.F.);
+#1178=ORIENTED_EDGE('',*,*,#820,.F.);
+#1179=ORIENTED_EDGE('',*,*,#826,.F.);
+#1180=ORIENTED_EDGE('',*,*,#856,.T.);
+#1181=ORIENTED_EDGE('',*,*,#822,.F.);
+#1182=ORIENTED_EDGE('',*,*,#828,.F.);
+#1183=ORIENTED_EDGE('',*,*,#834,.F.);
+#1184=ORIENTED_EDGE('',*,*,#857,.T.);
+#1185=ORIENTED_EDGE('',*,*,#830,.F.);
+#1186=ORIENTED_EDGE('',*,*,#836,.F.);
+#1187=ORIENTED_EDGE('',*,*,#842,.F.);
+#1188=ORIENTED_EDGE('',*,*,#858,.T.);
+#1189=ORIENTED_EDGE('',*,*,#838,.F.);
+#1190=ORIENTED_EDGE('',*,*,#843,.F.);
+#1191=ORIENTED_EDGE('',*,*,#789,.F.);
+#1192=ORIENTED_EDGE('',*,*,#859,.F.);
+#1193=ORIENTED_EDGE('',*,*,#776,.F.);
+#1194=ORIENTED_EDGE('',*,*,#860,.F.);
+#1195=ORIENTED_EDGE('',*,*,#844,.T.);
+#1196=ORIENTED_EDGE('',*,*,#861,.T.);
+#1197=ORIENTED_EDGE('',*,*,#862,.T.);
+#1198=ORIENTED_EDGE('',*,*,#863,.T.);
+#1199=ORIENTED_EDGE('',*,*,#864,.T.);
+#1200=ORIENTED_EDGE('',*,*,#865,.T.);
+#1201=ORIENTED_EDGE('',*,*,#866,.T.);
+#1202=ORIENTED_EDGE('',*,*,#867,.T.);
+#1203=ORIENTED_EDGE('',*,*,#868,.T.);
+#1204=ORIENTED_EDGE('',*,*,#869,.T.);
+#1205=ORIENTED_EDGE('',*,*,#870,.T.);
+#1206=ORIENTED_EDGE('',*,*,#871,.T.);
+#1207=ORIENTED_EDGE('',*,*,#872,.T.);
+#1208=ORIENTED_EDGE('',*,*,#873,.T.);
+#1209=ORIENTED_EDGE('',*,*,#874,.T.);
+#1210=ORIENTED_EDGE('',*,*,#875,.T.);
+#1211=ORIENTED_EDGE('',*,*,#876,.T.);
+#1212=ORIENTED_EDGE('',*,*,#877,.T.);
+#1213=ORIENTED_EDGE('',*,*,#850,.T.);
+#1214=ORIENTED_EDGE('',*,*,#878,.F.);
+#1215=ORIENTED_EDGE('',*,*,#879,.T.);
+#1216=ORIENTED_EDGE('',*,*,#880,.T.);
+#1217=ORIENTED_EDGE('',*,*,#881,.T.);
+#1218=ORIENTED_EDGE('',*,*,#882,.T.);
+#1219=ORIENTED_EDGE('',*,*,#847,.T.);
+#1220=ORIENTED_EDGE('',*,*,#853,.F.);
+#1221=ORIENTED_EDGE('',*,*,#851,.T.);
+#1222=ORIENTED_EDGE('',*,*,#877,.F.);
+#1223=ORIENTED_EDGE('',*,*,#883,.T.);
+#1224=ORIENTED_EDGE('',*,*,#884,.T.);
+#1225=ORIENTED_EDGE('',*,*,#885,.F.);
+#1226=ORIENTED_EDGE('',*,*,#861,.F.);
+#1227=ORIENTED_EDGE('',*,*,#882,.F.);
+#1228=ORIENTED_EDGE('',*,*,#886,.T.);
+#1229=ORIENTED_EDGE('',*,*,#724,.T.);
+#1230=ORIENTED_EDGE('',*,*,#886,.F.);
+#1231=ORIENTED_EDGE('',*,*,#881,.F.);
+#1232=ORIENTED_EDGE('',*,*,#887,.T.);
+#1233=ORIENTED_EDGE('',*,*,#706,.T.);
+#1234=ORIENTED_EDGE('',*,*,#887,.F.);
+#1235=ORIENTED_EDGE('',*,*,#880,.F.);
+#1236=ORIENTED_EDGE('',*,*,#888,.T.);
+#1237=ORIENTED_EDGE('',*,*,#712,.T.);
+#1238=ORIENTED_EDGE('',*,*,#888,.F.);
+#1239=ORIENTED_EDGE('',*,*,#879,.F.);
+#1240=ORIENTED_EDGE('',*,*,#889,.T.);
+#1241=ORIENTED_EDGE('',*,*,#718,.T.);
+#1242=ORIENTED_EDGE('',*,*,#889,.F.);
+#1243=ORIENTED_EDGE('',*,*,#840,.F.);
+#1244=ORIENTED_EDGE('',*,*,#890,.F.);
+#1245=ORIENTED_EDGE('',*,*,#839,.F.);
+#1246=ORIENTED_EDGE('',*,*,#858,.F.);
+#1247=ORIENTED_EDGE('',*,*,#841,.F.);
+#1248=ORIENTED_EDGE('',*,*,#890,.T.);
+#1249=ORIENTED_EDGE('',*,*,#891,.F.);
+#1250=ORIENTED_EDGE('',*,*,#864,.F.);
+#1251=ORIENTED_EDGE('',*,*,#892,.F.);
+#1252=ORIENTED_EDGE('',*,*,#893,.F.);
+#1253=ORIENTED_EDGE('',*,*,#817,.F.);
+#1254=ORIENTED_EDGE('',*,*,#894,.T.);
+#1255=ORIENTED_EDGE('',*,*,#815,.F.);
+#1256=ORIENTED_EDGE('',*,*,#855,.F.);
+#1257=ORIENTED_EDGE('',*,*,#895,.F.);
+#1258=ORIENTED_EDGE('',*,*,#874,.F.);
+#1259=ORIENTED_EDGE('',*,*,#896,.F.);
+#1260=ORIENTED_EDGE('',*,*,#897,.F.);
+#1261=ORIENTED_EDGE('',*,*,#816,.F.);
+#1262=ORIENTED_EDGE('',*,*,#894,.F.);
+#1263=ORIENTED_EDGE('',*,*,#832,.F.);
+#1264=ORIENTED_EDGE('',*,*,#898,.F.);
+#1265=ORIENTED_EDGE('',*,*,#831,.F.);
+#1266=ORIENTED_EDGE('',*,*,#857,.F.);
+#1267=ORIENTED_EDGE('',*,*,#833,.F.);
+#1268=ORIENTED_EDGE('',*,*,#898,.T.);
+#1269=ORIENTED_EDGE('',*,*,#899,.F.);
+#1270=ORIENTED_EDGE('',*,*,#900,.F.);
+#1271=ORIENTED_EDGE('',*,*,#901,.F.);
+#1272=ORIENTED_EDGE('',*,*,#867,.F.);
+#1273=ORIENTED_EDGE('',*,*,#825,.F.);
+#1274=ORIENTED_EDGE('',*,*,#902,.T.);
+#1275=ORIENTED_EDGE('',*,*,#823,.F.);
+#1276=ORIENTED_EDGE('',*,*,#856,.F.);
+#1277=ORIENTED_EDGE('',*,*,#903,.F.);
+#1278=ORIENTED_EDGE('',*,*,#871,.F.);
+#1279=ORIENTED_EDGE('',*,*,#904,.F.);
+#1280=ORIENTED_EDGE('',*,*,#905,.F.);
+#1281=ORIENTED_EDGE('',*,*,#824,.F.);
+#1282=ORIENTED_EDGE('',*,*,#902,.F.);
+#1283=ORIENTED_EDGE('',*,*,#892,.T.);
+#1284=ORIENTED_EDGE('',*,*,#863,.F.);
+#1285=ORIENTED_EDGE('',*,*,#906,.T.);
+#1286=ORIENTED_EDGE('',*,*,#907,.T.);
+#1287=ORIENTED_EDGE('',*,*,#896,.T.);
+#1288=ORIENTED_EDGE('',*,*,#873,.F.);
+#1289=ORIENTED_EDGE('',*,*,#908,.T.);
+#1290=ORIENTED_EDGE('',*,*,#909,.T.);
+#1291=ORIENTED_EDGE('',*,*,#901,.T.);
+#1292=ORIENTED_EDGE('',*,*,#910,.T.);
+#1293=ORIENTED_EDGE('',*,*,#911,.F.);
+#1294=ORIENTED_EDGE('',*,*,#868,.F.);
+#1295=ORIENTED_EDGE('',*,*,#899,.T.);
+#1296=ORIENTED_EDGE('',*,*,#866,.F.);
+#1297=ORIENTED_EDGE('',*,*,#912,.T.);
+#1298=ORIENTED_EDGE('',*,*,#913,.T.);
+#1299=ORIENTED_EDGE('',*,*,#893,.T.);
+#1300=ORIENTED_EDGE('',*,*,#907,.F.);
+#1301=ORIENTED_EDGE('',*,*,#914,.F.);
+#1302=ORIENTED_EDGE('',*,*,#884,.F.);
+#1303=ORIENTED_EDGE('',*,*,#915,.F.);
+#1304=ORIENTED_EDGE('',*,*,#916,.F.);
+#1305=ORIENTED_EDGE('',*,*,#897,.T.);
+#1306=ORIENTED_EDGE('',*,*,#909,.F.);
+#1307=ORIENTED_EDGE('',*,*,#917,.F.);
+#1308=ORIENTED_EDGE('',*,*,#905,.T.);
+#1309=ORIENTED_EDGE('',*,*,#918,.F.);
+#1310=ORIENTED_EDGE('',*,*,#919,.F.);
+#1311=ORIENTED_EDGE('',*,*,#910,.F.);
+#1312=ORIENTED_EDGE('',*,*,#900,.T.);
+#1313=ORIENTED_EDGE('',*,*,#913,.F.);
+#1314=ORIENTED_EDGE('',*,*,#920,.F.);
+#1315=ORIENTED_EDGE('',*,*,#904,.T.);
+#1316=ORIENTED_EDGE('',*,*,#870,.F.);
+#1317=ORIENTED_EDGE('',*,*,#921,.T.);
+#1318=ORIENTED_EDGE('',*,*,#918,.T.);
+#1319=ORIENTED_EDGE('',*,*,#903,.T.);
+#1320=ORIENTED_EDGE('',*,*,#917,.T.);
+#1321=ORIENTED_EDGE('',*,*,#908,.F.);
+#1322=ORIENTED_EDGE('',*,*,#872,.F.);
+#1323=ORIENTED_EDGE('',*,*,#869,.F.);
+#1324=ORIENTED_EDGE('',*,*,#911,.T.);
+#1325=ORIENTED_EDGE('',*,*,#919,.T.);
+#1326=ORIENTED_EDGE('',*,*,#921,.F.);
+#1327=ORIENTED_EDGE('',*,*,#891,.T.);
+#1328=ORIENTED_EDGE('',*,*,#920,.T.);
+#1329=ORIENTED_EDGE('',*,*,#912,.F.);
+#1330=ORIENTED_EDGE('',*,*,#865,.F.);
+#1331=ORIENTED_EDGE('',*,*,#749,.T.);
+#1332=ORIENTED_EDGE('',*,*,#764,.F.);
+#1333=ORIENTED_EDGE('',*,*,#765,.T.);
+#1334=ORIENTED_EDGE('',*,*,#758,.F.);
+#1335=ORIENTED_EDGE('',*,*,#760,.T.);
+#1336=ORIENTED_EDGE('',*,*,#752,.F.);
+#1337=ORIENTED_EDGE('',*,*,#754,.T.);
+#1338=ORIENTED_EDGE('',*,*,#745,.F.);
+#1339=ORIENTED_EDGE('',*,*,#862,.F.);
+#1340=ORIENTED_EDGE('',*,*,#885,.T.);
+#1341=ORIENTED_EDGE('',*,*,#914,.T.);
+#1342=ORIENTED_EDGE('',*,*,#906,.F.);
+#1343=ORIENTED_EDGE('',*,*,#876,.F.);
+#1344=ORIENTED_EDGE('',*,*,#922,.T.);
+#1345=ORIENTED_EDGE('',*,*,#915,.T.);
+#1346=ORIENTED_EDGE('',*,*,#883,.F.);
+#1347=ORIENTED_EDGE('',*,*,#895,.T.);
+#1348=ORIENTED_EDGE('',*,*,#916,.T.);
+#1349=ORIENTED_EDGE('',*,*,#922,.F.);
+#1350=ORIENTED_EDGE('',*,*,#875,.F.);
+#1351=ORIENTED_EDGE('',*,*,#777,.F.);
+#1352=ORIENTED_EDGE('',*,*,#859,.T.);
+#1353=ORIENTED_EDGE('',*,*,#791,.F.);
+#1354=ORIENTED_EDGE('',*,*,#809,.F.);
+#1355=ORIENTED_EDGE('',*,*,#771,.F.);
+#1356=ORIENTED_EDGE('',*,*,#878,.T.);
+#1357=ORIENTED_EDGE('',*,*,#849,.T.);
+#1358=ORIENTED_EDGE('',*,*,#852,.T.);
+#1359=ORIENTED_EDGE('',*,*,#845,.T.);
+#1360=ORIENTED_EDGE('',*,*,#860,.T.);
+#1361=ORIENTED_EDGE('',*,*,#778,.F.);
+#1362=ORIENTED_EDGE('',*,*,#810,.F.);
+#1363=ORIENTED_EDGE('',*,*,#783,.F.);
+#1364=ORIENTED_EDGE('',*,*,#854,.T.);
+#1365=ORIENTED_EDGE('',*,*,#772,.F.);
+#1366=ORIENTED_EDGE('',*,*,#785,.F.);
+#1367=CYLINDRICAL_SURFACE('',#1517,3.75);
+#1368=CYLINDRICAL_SURFACE('',#1522,3.75);
+#1369=CYLINDRICAL_SURFACE('',#1528,3.75);
+#1370=CYLINDRICAL_SURFACE('',#1534,3.75);
+#1371=CYLINDRICAL_SURFACE('',#1554,2.);
+#1372=CYLINDRICAL_SURFACE('',#1558,2.);
+#1373=CYLINDRICAL_SURFACE('',#1562,2.);
+#1374=CYLINDRICAL_SURFACE('',#1566,2.);
+#1375=CYLINDRICAL_SURFACE('',#1574,2.);
+#1376=CYLINDRICAL_SURFACE('',#1580,2.);
+#1377=CYLINDRICAL_SURFACE('',#1586,2.);
+#1378=CYLINDRICAL_SURFACE('',#1588,2.);
+#1379=CYLINDRICAL_SURFACE('',#1593,2.);
+#1380=CYLINDRICAL_SURFACE('',#1601,2.);
+#1381=CYLINDRICAL_SURFACE('',#1612,2.);
+#1382=CYLINDRICAL_SURFACE('',#1619,2.);
+#1383=CYLINDRICAL_SURFACE('',#1620,2.);
+#1384=CYLINDRICAL_SURFACE('',#1621,175.);
+#1385=CYLINDRICAL_SURFACE('',#1623,10.);
+#1386=CYLINDRICAL_SURFACE('',#1628,10.);
+#1387=CYLINDRICAL_SURFACE('',#1632,175.000000000002);
+#1388=CYLINDRICAL_SURFACE('',#1634,10.);
+#1389=CYLINDRICAL_SURFACE('',#1639,10.);
+#1390=CYLINDRICAL_SURFACE('',#1643,175.);
+#1391=CYLINDRICAL_SURFACE('',#1645,8.5);
+#1392=CYLINDRICAL_SURFACE('',#1648,8.5);
+#1393=CYLINDRICAL_SURFACE('',#1673,2.5);
+#1394=CYLINDRICAL_SURFACE('',#1674,2.5);
+#1395=CYLINDRICAL_SURFACE('',#1675,2.5);
+#1396=CYLINDRICAL_SURFACE('',#1676,2.5);
+#1397=CYLINDRICAL_SURFACE('',#1679,5.);
+#1398=CYLINDRICAL_SURFACE('',#1680,5.);
+#1399=CYLINDRICAL_SURFACE('',#1682,5.);
+#1400=CYLINDRICAL_SURFACE('',#1684,5.);
+#1401=CYLINDRICAL_SURFACE('',#1689,5.00000000000001);
+#1402=CYLINDRICAL_SURFACE('',#1690,5.00000000000001);
+#1403=CYLINDRICAL_SURFACE('',#1692,5.00000000000001);
+#1404=CYLINDRICAL_SURFACE('',#1694,5.00000000000001);
+#1405=CYLINDRICAL_SURFACE('',#1697,172.);
+#1406=CYLINDRICAL_SURFACE('',#1700,7.);
+#1407=CYLINDRICAL_SURFACE('',#1702,7.);
+#1408=CYLINDRICAL_SURFACE('',#1709,7.);
+#1409=CYLINDRICAL_SURFACE('',#1710,7.);
+#1410=CYLINDRICAL_SURFACE('',#1711,178.000000000002);
+#1411=CYLINDRICAL_SURFACE('',#1715,172.);
+#1412=ADVANCED_FACE('',(#66),#1367,.F.);
+#1413=ADVANCED_FACE('',(#67,#30),#40,.T.);
+#1414=ADVANCED_FACE('',(#68),#1368,.F.);
+#1415=ADVANCED_FACE('',(#69,#31),#41,.T.);
+#1416=ADVANCED_FACE('',(#70),#1369,.F.);
+#1417=ADVANCED_FACE('',(#71,#32),#42,.T.);
+#1418=ADVANCED_FACE('',(#72),#1370,.F.);
+#1419=ADVANCED_FACE('',(#73,#33),#43,.T.);
+#1420=ADVANCED_FACE('',(#74),#44,.T.);
+#1421=ADVANCED_FACE('',(#75),#1371,.F.);
+#1422=ADVANCED_FACE('',(#76),#45,.F.);
+#1423=ADVANCED_FACE('',(#77),#1372,.F.);
+#1424=ADVANCED_FACE('',(#78),#46,.F.);
+#1425=ADVANCED_FACE('',(#79),#1373,.F.);
+#1426=ADVANCED_FACE('',(#80),#47,.F.);
+#1427=ADVANCED_FACE('',(#81),#1374,.F.);
+#1428=ADVANCED_FACE('',(#82),#48,.F.);
+#1429=ADVANCED_FACE('',(#83),#28,.T.);
+#1430=ADVANCED_FACE('',(#84),#1375,.T.);
+#1431=ADVANCED_FACE('',(#85),#29,.T.);
+#1432=ADVANCED_FACE('',(#86),#1376,.T.);
+#1433=ADVANCED_FACE('',(#87),#19,.T.);
+#1434=ADVANCED_FACE('',(#88),#1377,.F.);
+#1435=ADVANCED_FACE('',(#89),#1378,.T.);
+#1436=ADVANCED_FACE('',(#90),#20,.T.);
+#1437=ADVANCED_FACE('',(#91),#1379,.F.);
+#1438=ADVANCED_FACE('',(#92),#21,.T.);
+#1439=ADVANCED_FACE('',(#93),#22,.T.);
+#1440=ADVANCED_FACE('',(#94),#1380,.T.);
+#1441=ADVANCED_FACE('',(#95),#23,.T.);
+#1442=ADVANCED_FACE('',(#96),#24,.T.);
+#1443=ADVANCED_FACE('',(#97),#25,.T.);
+#1444=ADVANCED_FACE('',(#98),#1381,.T.);
+#1445=ADVANCED_FACE('',(#99),#26,.T.);
+#1446=ADVANCED_FACE('',(#100),#27,.T.);
+#1447=ADVANCED_FACE('',(#101),#1382,.T.);
+#1448=ADVANCED_FACE('',(#102),#1383,.T.);
+#1449=ADVANCED_FACE('',(#103),#1384,.T.);
+#1450=ADVANCED_FACE('',(#104),#1385,.T.);
+#1451=ADVANCED_FACE('',(#105),#49,.T.);
+#1452=ADVANCED_FACE('',(#106),#1386,.T.);
+#1453=ADVANCED_FACE('',(#107),#1387,.F.);
+#1454=ADVANCED_FACE('',(#108),#1388,.T.);
+#1455=ADVANCED_FACE('',(#109,#34),#50,.T.);
+#1456=ADVANCED_FACE('',(#110),#1389,.T.);
+#1457=ADVANCED_FACE('',(#111),#1390,.T.);
+#1458=ADVANCED_FACE('',(#112),#1391,.F.);
+#1459=ADVANCED_FACE('',(#113),#1392,.F.);
+#1460=ADVANCED_FACE('',(#114),#51,.F.);
+#1461=ADVANCED_FACE('',(#115,#35,#36,#37,#38),#52,.F.);
+#1462=ADVANCED_FACE('',(#116),#53,.F.);
+#1463=ADVANCED_FACE('',(#117),#1393,.F.);
+#1464=ADVANCED_FACE('',(#118),#1394,.F.);
+#1465=ADVANCED_FACE('',(#119),#1395,.F.);
+#1466=ADVANCED_FACE('',(#120),#1396,.F.);
+#1467=ADVANCED_FACE('',(#121),#54,.F.);
+#1468=ADVANCED_FACE('',(#122),#1397,.T.);
+#1469=ADVANCED_FACE('',(#123),#1398,.T.);
+#1470=ADVANCED_FACE('',(#124),#1399,.T.);
+#1471=ADVANCED_FACE('',(#125),#1400,.T.);
+#1472=ADVANCED_FACE('',(#126),#55,.F.);
+#1473=ADVANCED_FACE('',(#127),#56,.F.);
+#1474=ADVANCED_FACE('',(#128),#1401,.T.);
+#1475=ADVANCED_FACE('',(#129),#1402,.T.);
+#1476=ADVANCED_FACE('',(#130),#1403,.T.);
+#1477=ADVANCED_FACE('',(#131),#1404,.T.);
+#1478=ADVANCED_FACE('',(#132),#57,.F.);
+#1479=ADVANCED_FACE('',(#133),#1405,.F.);
+#1480=ADVANCED_FACE('',(#134),#58,.F.);
+#1481=ADVANCED_FACE('',(#135),#1406,.F.);
+#1482=ADVANCED_FACE('',(#136),#1407,.F.);
+#1483=ADVANCED_FACE('',(#137),#59,.F.);
+#1484=ADVANCED_FACE('',(#138),#1408,.F.);
+#1485=ADVANCED_FACE('',(#139),#1409,.F.);
+#1486=ADVANCED_FACE('',(#140),#1410,.T.);
+#1487=ADVANCED_FACE('',(#141,#39),#60,.F.);
+#1488=ADVANCED_FACE('',(#142),#61,.F.);
+#1489=ADVANCED_FACE('',(#143),#62,.F.);
+#1490=ADVANCED_FACE('',(#144),#1411,.F.);
+#1491=ADVANCED_FACE('',(#145),#63,.T.);
+#1492=ADVANCED_FACE('',(#146),#64,.T.);
+#1493=ADVANCED_FACE('',(#147),#65,.T.);
+#1494=CLOSED_SHELL('',(#1412,#1413,#1414,#1415,#1416,#1417,#1418,#1419,
+#1420,#1421,#1422,#1423,#1424,#1425,#1426,#1427,#1428,#1429,#1430,#1431,
+#1432,#1433,#1434,#1435,#1436,#1437,#1438,#1439,#1440,#1441,#1442,#1443,
+#1444,#1445,#1446,#1447,#1448,#1449,#1450,#1451,#1452,#1453,#1454,#1455,
+#1456,#1457,#1458,#1459,#1460,#1461,#1462,#1463,#1464,#1465,#1466,#1467,
+#1468,#1469,#1470,#1471,#1472,#1473,#1474,#1475,#1476,#1477,#1478,#1479,
+#1480,#1481,#1482,#1483,#1484,#1485,#1486,#1487,#1488,#1489,#1490,#1491,
+#1492,#1493));
+#1495=DERIVED_UNIT_ELEMENT(#1498,1.);
+#1496=DERIVED_UNIT_ELEMENT(#2733,-3.);
+#1497=DIMENSIONAL_EXPONENTS(0.,1.,0.,0.,0.,0.,0.);
+#1498=(
+CONVERSION_BASED_UNIT('gram',#1500)
+MASS_UNIT()
+NAMED_UNIT(#1497)
+);
+#1499=(
+MASS_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.KILO.,.GRAM.)
+);
+#1500=MASS_MEASURE_WITH_UNIT(MASS_MEASURE(0.001),#1499);
+#1501=DERIVED_UNIT((#1495,#1496));
+#1502=MEASURE_REPRESENTATION_ITEM('density measure',
+POSITIVE_RATIO_MEASURE(1.),#1501);
+#1503=PROPERTY_DEFINITION_REPRESENTATION(#1508,#1505);
+#1504=PROPERTY_DEFINITION_REPRESENTATION(#1509,#1506);
+#1505=REPRESENTATION('material name',(#1507),#2730);
+#1506=REPRESENTATION('density',(#1502),#2730);
+#1507=DESCRIPTIVE_REPRESENTATION_ITEM('Generisch','Generisch');
+#1508=PROPERTY_DEFINITION('material property','material name',#2740);
+#1509=PROPERTY_DEFINITION('material property','density of part',#2740);
+#1510=DATE_TIME_ROLE('creation_date');
+#1511=APPLIED_DATE_AND_TIME_ASSIGNMENT(#1512,#1510,(#2740));
+#1512=DATE_AND_TIME(#1513,#1514);
+#1513=CALENDAR_DATE(2025,7,1);
+#1514=LOCAL_TIME(0,0,0.,#1515);
+#1515=COORDINATED_UNIVERSAL_TIME_OFFSET(0,0,.BEHIND.);
+#1516=AXIS2_PLACEMENT_3D('',#2222,#1719,#1720);
+#1517=AXIS2_PLACEMENT_3D('',#2223,#1721,#1722);
+#1518=AXIS2_PLACEMENT_3D('',#2239,#1723,#1724);
+#1519=AXIS2_PLACEMENT_3D('',#2248,#1726,#1727);
+#1520=AXIS2_PLACEMENT_3D('',#2249,#1728,#1729);
+#1521=AXIS2_PLACEMENT_3D('',#2251,#1730,#1731);
+#1522=AXIS2_PLACEMENT_3D('',#2252,#1732,#1733);
+#1523=AXIS2_PLACEMENT_3D('',#2272,#1734,#1735);
+#1524=AXIS2_PLACEMENT_3D('',#2275,#1737,#1738);
+#1525=AXIS2_PLACEMENT_3D('',#2276,#1739,#1740);
+#1526=AXIS2_PLACEMENT_3D('',#2277,#1741,#1742);
+#1527=AXIS2_PLACEMENT_3D('',#2279,#1743,#1744);
+#1528=AXIS2_PLACEMENT_3D('',#2280,#1745,#1746);
+#1529=AXIS2_PLACEMENT_3D('',#2300,#1747,#1748);
+#1530=AXIS2_PLACEMENT_3D('',#2303,#1750,#1751);
+#1531=AXIS2_PLACEMENT_3D('',#2304,#1752,#1753);
+#1532=AXIS2_PLACEMENT_3D('',#2305,#1754,#1755);
+#1533=AXIS2_PLACEMENT_3D('',#2307,#1756,#1757);
+#1534=AXIS2_PLACEMENT_3D('',#2308,#1758,#1759);
+#1535=AXIS2_PLACEMENT_3D('',#2324,#1760,#1761);
+#1536=AXIS2_PLACEMENT_3D('',#2327,#1763,#1764);
+#1537=AXIS2_PLACEMENT_3D('',#2328,#1765,#1766);
+#1538=AXIS2_PLACEMENT_3D('',#2329,#1767,#1768);
+#1539=AXIS2_PLACEMENT_3D('',#2331,#1769,#1770);
+#1540=AXIS2_PLACEMENT_3D('',#2332,#1771,#1772);
+#1541=AXIS2_PLACEMENT_3D('',#2334,#1773,#1774);
+#1542=AXIS2_PLACEMENT_3D('',#2336,#1775,#1776);
+#1543=AXIS2_PLACEMENT_3D('',#2338,#1777,#1778);
+#1544=AXIS2_PLACEMENT_3D('',#2346,#1782,#1783);
+#1545=AXIS2_PLACEMENT_3D('',#2348,#1784,#1785);
+#1546=AXIS2_PLACEMENT_3D('',#2349,#1786,#1787);
+#1547=AXIS2_PLACEMENT_3D('',#2351,#1788,#1789);
+#1548=AXIS2_PLACEMENT_3D('',#2354,#1791,#1792);
+#1549=AXIS2_PLACEMENT_3D('',#2356,#1793,#1794);
+#1550=AXIS2_PLACEMENT_3D('',#2358,#1795,#1796);
+#1551=AXIS2_PLACEMENT_3D('',#2359,#1797,#1798);
+#1552=AXIS2_PLACEMENT_3D('',#2361,#1799,#1800);
+#1553=AXIS2_PLACEMENT_3D('',#2364,#1802,#1803);
+#1554=AXIS2_PLACEMENT_3D('',#2365,#1804,#1805);
+#1555=AXIS2_PLACEMENT_3D('',#2368,#1806,#1807);
+#1556=AXIS2_PLACEMENT_3D('',#2372,#1809,#1810);
+#1557=AXIS2_PLACEMENT_3D('',#2374,#1812,#1813);
+#1558=AXIS2_PLACEMENT_3D('',#2380,#1817,#1818);
+#1559=AXIS2_PLACEMENT_3D('',#2383,#1819,#1820);
+#1560=AXIS2_PLACEMENT_3D('',#2387,#1822,#1823);
+#1561=AXIS2_PLACEMENT_3D('',#2389,#1825,#1826);
+#1562=AXIS2_PLACEMENT_3D('',#2392,#1829,#1830);
+#1563=AXIS2_PLACEMENT_3D('',#2395,#1831,#1832);
+#1564=AXIS2_PLACEMENT_3D('',#2399,#1834,#1835);
+#1565=AXIS2_PLACEMENT_3D('',#2401,#1837,#1838);
+#1566=AXIS2_PLACEMENT_3D('',#2404,#1841,#1842);
+#1567=AXIS2_PLACEMENT_3D('',#2406,#1843,#1844);
+#1568=AXIS2_PLACEMENT_3D('',#2409,#1846,#1847);
+#1569=AXIS2_PLACEMENT_3D('',#2410,#1848,#1849);
+#1570=AXIS2_PLACEMENT_3D('',#2413,#1852,#1853);
+#1571=AXIS2_PLACEMENT_3D('',#2415,#1854,#1855);
+#1572=AXIS2_PLACEMENT_3D('',#2417,#1856,#1857);
+#1573=AXIS2_PLACEMENT_3D('',#2418,#1858,#1859);
+#1574=AXIS2_PLACEMENT_3D('',#2419,#1860,#1861);
+#1575=AXIS2_PLACEMENT_3D('',#2422,#1862,#1863);
+#1576=AXIS2_PLACEMENT_3D('',#2425,#1866,#1867);
+#1577=AXIS2_PLACEMENT_3D('',#2427,#1868,#1869);
+#1578=AXIS2_PLACEMENT_3D('',#2429,#1870,#1871);
+#1579=AXIS2_PLACEMENT_3D('',#2430,#1872,#1873);
+#1580=AXIS2_PLACEMENT_3D('',#2431,#1874,#1875);
+#1581=AXIS2_PLACEMENT_3D('',#2434,#1876,#1877);
+#1582=AXIS2_PLACEMENT_3D('',#2437,#1880,#1881);
+#1583=AXIS2_PLACEMENT_3D('',#2439,#1882,#1883);
+#1584=AXIS2_PLACEMENT_3D('',#2441,#1884,#1885);
+#1585=AXIS2_PLACEMENT_3D('',#2442,#1886,#1887);
+#1586=AXIS2_PLACEMENT_3D('',#2443,#1888,#1889);
+#1587=AXIS2_PLACEMENT_3D('',#2446,#1890,#1891);
+#1588=AXIS2_PLACEMENT_3D('',#2449,#1894,#1895);
+#1589=AXIS2_PLACEMENT_3D('',#2451,#1897,#1898);
+#1590=AXIS2_PLACEMENT_3D('',#2453,#1899,#1900);
+#1591=AXIS2_PLACEMENT_3D('',#2455,#1901,#1902);
+#1592=AXIS2_PLACEMENT_3D('',#2456,#1903,#1904);
+#1593=AXIS2_PLACEMENT_3D('',#2457,#1905,#1906);
+#1594=AXIS2_PLACEMENT_3D('',#2460,#1907,#1908);
+#1595=AXIS2_PLACEMENT_3D('',#2463,#1911,#1912);
+#1596=AXIS2_PLACEMENT_3D('',#2465,#1913,#1914);
+#1597=AXIS2_PLACEMENT_3D('',#2466,#1915,#1916);
+#1598=AXIS2_PLACEMENT_3D('',#2467,#1917,#1918);
+#1599=AXIS2_PLACEMENT_3D('',#2469,#1919,#1920);
+#1600=AXIS2_PLACEMENT_3D('',#2470,#1921,#1922);
+#1601=AXIS2_PLACEMENT_3D('',#2471,#1923,#1924);
+#1602=AXIS2_PLACEMENT_3D('',#2473,#1925,#1926);
+#1603=AXIS2_PLACEMENT_3D('',#2475,#1928,#1929);
+#1604=AXIS2_PLACEMENT_3D('',#2477,#1930,#1931);
+#1605=AXIS2_PLACEMENT_3D('',#2478,#1932,#1933);
+#1606=AXIS2_PLACEMENT_3D('',#2479,#1934,#1935);
+#1607=AXIS2_PLACEMENT_3D('',#2481,#1936,#1937);
+#1608=AXIS2_PLACEMENT_3D('',#2482,#1938,#1939);
+#1609=AXIS2_PLACEMENT_3D('',#2483,#1940,#1941);
+#1610=AXIS2_PLACEMENT_3D('',#2485,#1942,#1943);
+#1611=AXIS2_PLACEMENT_3D('',#2486,#1944,#1945);
+#1612=AXIS2_PLACEMENT_3D('',#2487,#1946,#1947);
+#1613=AXIS2_PLACEMENT_3D('',#2489,#1948,#1949);
+#1614=AXIS2_PLACEMENT_3D('',#2491,#1951,#1952);
+#1615=AXIS2_PLACEMENT_3D('',#2493,#1953,#1954);
+#1616=AXIS2_PLACEMENT_3D('',#2494,#1955,#1956);
+#1617=AXIS2_PLACEMENT_3D('',#2495,#1957,#1958);
+#1618=AXIS2_PLACEMENT_3D('',#2496,#1959,#1960);
+#1619=AXIS2_PLACEMENT_3D('',#2497,#1961,#1962);
+#1620=AXIS2_PLACEMENT_3D('',#2499,#1964,#1965);
+#1621=AXIS2_PLACEMENT_3D('',#2501,#1967,#1968);
+#1622=AXIS2_PLACEMENT_3D('',#2504,#1970,#1971);
+#1623=AXIS2_PLACEMENT_3D('',#2505,#1972,#1973);
+#1624=AXIS2_PLACEMENT_3D('',#2509,#1975,#1976);
+#1625=AXIS2_PLACEMENT_3D('',#2513,#1978,#1979);
+#1626=AXIS2_PLACEMENT_3D('',#2516,#1981,#1982);
+#1627=AXIS2_PLACEMENT_3D('',#2517,#1983,#1984);
+#1628=AXIS2_PLACEMENT_3D('',#2521,#1987,#1988);
+#1629=AXIS2_PLACEMENT_3D('',#2525,#1990,#1991);
+#1630=AXIS2_PLACEMENT_3D('',#2529,#1993,#1994);
+#1631=AXIS2_PLACEMENT_3D('',#2532,#1996,#1997);
+#1632=AXIS2_PLACEMENT_3D('',#2533,#1998,#1999);
+#1633=AXIS2_PLACEMENT_3D('',#2536,#2001,#2002);
+#1634=AXIS2_PLACEMENT_3D('',#2537,#2003,#2004);
+#1635=AXIS2_PLACEMENT_3D('',#2541,#2006,#2007);
+#1636=AXIS2_PLACEMENT_3D('',#2545,#2009,#2010);
+#1637=AXIS2_PLACEMENT_3D('',#2548,#2012,#2013);
+#1638=AXIS2_PLACEMENT_3D('',#2549,#2014,#2015);
+#1639=AXIS2_PLACEMENT_3D('',#2553,#2018,#2019);
+#1640=AXIS2_PLACEMENT_3D('',#2557,#2021,#2022);
+#1641=AXIS2_PLACEMENT_3D('',#2561,#2024,#2025);
+#1642=AXIS2_PLACEMENT_3D('',#2564,#2027,#2028);
+#1643=AXIS2_PLACEMENT_3D('',#2565,#2029,#2030);
+#1644=AXIS2_PLACEMENT_3D('',#2566,#2031,#2032);
+#1645=AXIS2_PLACEMENT_3D('',#2567,#2033,#2034);
+#1646=AXIS2_PLACEMENT_3D('',#2572,#2036,#2037);
+#1647=AXIS2_PLACEMENT_3D('',#2575,#2039,#2040);
+#1648=AXIS2_PLACEMENT_3D('',#2576,#2041,#2042);
+#1649=AXIS2_PLACEMENT_3D('',#2581,#2044,#2045);
+#1650=AXIS2_PLACEMENT_3D('',#2584,#2047,#2048);
+#1651=AXIS2_PLACEMENT_3D('',#2585,#2049,#2050);
+#1652=AXIS2_PLACEMENT_3D('',#2588,#2053,#2054);
+#1653=AXIS2_PLACEMENT_3D('',#2590,#2056,#2057);
+#1654=AXIS2_PLACEMENT_3D('',#2591,#2058,#2059);
+#1655=AXIS2_PLACEMENT_3D('',#2592,#2060,#2061);
+#1656=AXIS2_PLACEMENT_3D('',#2593,#2062,#2063);
+#1657=AXIS2_PLACEMENT_3D('',#2601,#2068,#2069);
+#1658=AXIS2_PLACEMENT_3D('',#2603,#2070,#2071);
+#1659=AXIS2_PLACEMENT_3D('',#2607,#2073,#2074);
+#1660=AXIS2_PLACEMENT_3D('',#2609,#2075,#2076);
+#1661=AXIS2_PLACEMENT_3D('',#2611,#2077,#2078);
+#1662=AXIS2_PLACEMENT_3D('',#2613,#2079,#2080);
+#1663=AXIS2_PLACEMENT_3D('',#2615,#2081,#2082);
+#1664=AXIS2_PLACEMENT_3D('',#2617,#2083,#2084);
+#1665=AXIS2_PLACEMENT_3D('',#2619,#2085,#2086);
+#1666=AXIS2_PLACEMENT_3D('',#2623,#2088,#2089);
+#1667=AXIS2_PLACEMENT_3D('',#2625,#2090,#2091);
+#1668=AXIS2_PLACEMENT_3D('',#2631,#2095,#2096);
+#1669=AXIS2_PLACEMENT_3D('',#2633,#2097,#2098);
+#1670=AXIS2_PLACEMENT_3D('',#2635,#2099,#2100);
+#1671=AXIS2_PLACEMENT_3D('',#2637,#2101,#2102);
+#1672=AXIS2_PLACEMENT_3D('',#2638,#2103,#2104);
+#1673=AXIS2_PLACEMENT_3D('',#2644,#2108,#2109);
+#1674=AXIS2_PLACEMENT_3D('',#2646,#2111,#2112);
+#1675=AXIS2_PLACEMENT_3D('',#2648,#2114,#2115);
+#1676=AXIS2_PLACEMENT_3D('',#2650,#2117,#2118);
+#1677=AXIS2_PLACEMENT_3D('',#2652,#2120,#2121);
+#1678=AXIS2_PLACEMENT_3D('',#2653,#2122,#2123);
+#1679=AXIS2_PLACEMENT_3D('',#2654,#2124,#2125);
+#1680=AXIS2_PLACEMENT_3D('',#2655,#2126,#2127);
+#1681=AXIS2_PLACEMENT_3D('',#2660,#2130,#2131);
+#1682=AXIS2_PLACEMENT_3D('',#2661,#2132,#2133);
+#1683=AXIS2_PLACEMENT_3D('',#2662,#2134,#2135);
+#1684=AXIS2_PLACEMENT_3D('',#2663,#2136,#2137);
+#1685=AXIS2_PLACEMENT_3D('',#2668,#2140,#2141);
+#1686=AXIS2_PLACEMENT_3D('',#2669,#2142,#2143);
+#1687=AXIS2_PLACEMENT_3D('',#2670,#2144,#2145);
+#1688=AXIS2_PLACEMENT_3D('',#2671,#2146,#2147);
+#1689=AXIS2_PLACEMENT_3D('',#2672,#2148,#2149);
+#1690=AXIS2_PLACEMENT_3D('',#2673,#2150,#2151);
+#1691=AXIS2_PLACEMENT_3D('',#2677,#2153,#2154);
+#1692=AXIS2_PLACEMENT_3D('',#2679,#2156,#2157);
+#1693=AXIS2_PLACEMENT_3D('',#2680,#2158,#2159);
+#1694=AXIS2_PLACEMENT_3D('',#2681,#2160,#2161);
+#1695=AXIS2_PLACEMENT_3D('',#2686,#2164,#2165);
+#1696=AXIS2_PLACEMENT_3D('',#2687,#2166,#2167);
+#1697=AXIS2_PLACEMENT_3D('',#2688,#2168,#2169);
+#1698=AXIS2_PLACEMENT_3D('',#2691,#2171,#2172);
+#1699=AXIS2_PLACEMENT_3D('',#2692,#2173,#2174);
+#1700=AXIS2_PLACEMENT_3D('',#2696,#2177,#2178);
+#1701=AXIS2_PLACEMENT_3D('',#2698,#2179,#2180);
+#1702=AXIS2_PLACEMENT_3D('',#2700,#2182,#2183);
+#1703=AXIS2_PLACEMENT_3D('',#2703,#2185,#2186);
+#1704=AXIS2_PLACEMENT_3D('',#2704,#2187,#2188);
+#1705=AXIS2_PLACEMENT_3D('',#2708,#2191,#2192);
+#1706=AXIS2_PLACEMENT_3D('',#2709,#2193,#2194);
+#1707=AXIS2_PLACEMENT_3D('',#2711,#2195,#2196);
+#1708=AXIS2_PLACEMENT_3D('',#2712,#2197,#2198);
+#1709=AXIS2_PLACEMENT_3D('',#2714,#2200,#2201);
+#1710=AXIS2_PLACEMENT_3D('',#2716,#2203,#2204);
+#1711=AXIS2_PLACEMENT_3D('',#2717,#2205,#2206);
+#1712=AXIS2_PLACEMENT_3D('',#2718,#2207,#2208);
+#1713=AXIS2_PLACEMENT_3D('',#2719,#2209,#2210);
+#1714=AXIS2_PLACEMENT_3D('',#2720,#2211,#2212);
+#1715=AXIS2_PLACEMENT_3D('',#2722,#2214,#2215);
+#1716=AXIS2_PLACEMENT_3D('',#2723,#2216,#2217);
+#1717=AXIS2_PLACEMENT_3D('',#2724,#2218,#2219);
+#1718=AXIS2_PLACEMENT_3D('',#2725,#2220,#2221);
+#1719=DIRECTION('axis',(0.,0.,1.));
+#1720=DIRECTION('refdir',(1.,0.,0.));
+#1721=DIRECTION('center_axis',(0.,0.,-1.));
+#1722=DIRECTION('ref_axis',(1.,0.,0.));
+#1723=DIRECTION('center_axis',(0.,0.,-1.));
+#1724=DIRECTION('ref_axis',(1.,0.,0.));
+#1725=DIRECTION('',(0.,0.,-1.));
+#1726=DIRECTION('center_axis',(0.,0.,-1.));
+#1727=DIRECTION('ref_axis',(1.,0.,0.));
+#1728=DIRECTION('center_axis',(0.,0.,1.));
+#1729=DIRECTION('ref_axis',(1.,0.,0.));
+#1730=DIRECTION('center_axis',(0.,0.,1.));
+#1731=DIRECTION('ref_axis',(-1.,0.,0.));
+#1732=DIRECTION('center_axis',(0.,0.,-1.));
+#1733=DIRECTION('ref_axis',(1.,0.,0.));
+#1734=DIRECTION('center_axis',(0.,0.,-1.));
+#1735=DIRECTION('ref_axis',(1.,0.,0.));
+#1736=DIRECTION('',(0.,0.,-1.));
+#1737=DIRECTION('center_axis',(0.,0.,-1.));
+#1738=DIRECTION('ref_axis',(1.,0.,0.));
+#1739=DIRECTION('center_axis',(0.,0.,-1.));
+#1740=DIRECTION('ref_axis',(1.,0.,0.));
+#1741=DIRECTION('center_axis',(0.,0.,1.));
+#1742=DIRECTION('ref_axis',(1.,0.,0.));
+#1743=DIRECTION('center_axis',(0.,0.,1.));
+#1744=DIRECTION('ref_axis',(-1.,0.,0.));
+#1745=DIRECTION('center_axis',(0.,0.,-1.));
+#1746=DIRECTION('ref_axis',(1.,0.,0.));
+#1747=DIRECTION('center_axis',(0.,0.,-1.));
+#1748=DIRECTION('ref_axis',(1.,0.,0.));
+#1749=DIRECTION('',(0.,0.,-1.));
+#1750=DIRECTION('center_axis',(0.,0.,-1.));
+#1751=DIRECTION('ref_axis',(1.,0.,0.));
+#1752=DIRECTION('center_axis',(0.,0.,-1.));
+#1753=DIRECTION('ref_axis',(1.,0.,0.));
+#1754=DIRECTION('center_axis',(0.,0.,1.));
+#1755=DIRECTION('ref_axis',(1.,0.,0.));
+#1756=DIRECTION('center_axis',(0.,0.,1.));
+#1757=DIRECTION('ref_axis',(-1.,0.,0.));
+#1758=DIRECTION('center_axis',(0.,0.,-1.));
+#1759=DIRECTION('ref_axis',(1.,0.,0.));
+#1760=DIRECTION('center_axis',(0.,0.,-1.));
+#1761=DIRECTION('ref_axis',(1.,0.,0.));
+#1762=DIRECTION('',(0.,0.,-1.));
+#1763=DIRECTION('center_axis',(0.,0.,-1.));
+#1764=DIRECTION('ref_axis',(1.,0.,0.));
+#1765=DIRECTION('center_axis',(0.,0.,-1.));
+#1766=DIRECTION('ref_axis',(1.,0.,0.));
+#1767=DIRECTION('center_axis',(0.,0.,1.));
+#1768=DIRECTION('ref_axis',(1.,0.,0.));
+#1769=DIRECTION('center_axis',(0.,0.,1.));
+#1770=DIRECTION('ref_axis',(-1.,0.,0.));
+#1771=DIRECTION('center_axis',(0.,0.,1.));
+#1772=DIRECTION('ref_axis',(1.,0.,0.));
+#1773=DIRECTION('center_axis',(0.,0.,-1.));
+#1774=DIRECTION('ref_axis',(-0.825722823844769,-0.564076074817768,0.));
+#1775=DIRECTION('center_axis',(0.,0.,-1.));
+#1776=DIRECTION('ref_axis',(-0.260496577422837,-0.96547477085162,0.));
+#1777=DIRECTION('center_axis',(0.,0.,1.));
+#1778=DIRECTION('ref_axis',(0.762837403353299,0.646590361856096,0.));
+#1779=DIRECTION('',(0.,1.,0.));
+#1780=DIRECTION('',(-1.,0.,0.));
+#1781=DIRECTION('',(0.,-1.,0.));
+#1782=DIRECTION('center_axis',(0.,0.,1.));
+#1783=DIRECTION('ref_axis',(-0.762837403353299,0.646590361856096,0.));
+#1784=DIRECTION('center_axis',(0.,0.,-1.));
+#1785=DIRECTION('ref_axis',(0.260496577422837,-0.96547477085162,0.));
+#1786=DIRECTION('center_axis',(0.,0.,-1.));
+#1787=DIRECTION('ref_axis',(0.82572282384477,-0.564076074817767,0.));
+#1788=DIRECTION('center_axis',(0.,0.,-1.));
+#1789=DIRECTION('ref_axis',(0.82572282384477,-0.564076074817767,0.));
+#1790=DIRECTION('',(4.58956396800653E-16,-1.,0.));
+#1791=DIRECTION('center_axis',(0.,0.,-1.));
+#1792=DIRECTION('ref_axis',(0.581238193719097,0.813733471206735,0.));
+#1793=DIRECTION('center_axis',(0.,0.,-1.));
+#1794=DIRECTION('ref_axis',(0.581238193719097,0.813733471206735,0.));
+#1795=DIRECTION('center_axis',(0.,0.,1.));
+#1796=DIRECTION('ref_axis',(1.23710565601088E-16,-1.,0.));
+#1797=DIRECTION('center_axis',(0.,0.,-1.));
+#1798=DIRECTION('ref_axis',(-0.581238193719097,0.813733471206735,0.));
+#1799=DIRECTION('center_axis',(0.,0.,-1.));
+#1800=DIRECTION('ref_axis',(-0.581238193719097,0.813733471206735,0.));
+#1801=DIRECTION('',(9.17912793601306E-16,1.,0.));
+#1802=DIRECTION('center_axis',(0.,0.,-1.));
+#1803=DIRECTION('ref_axis',(-0.825722823844769,-0.564076074817768,0.));
+#1804=DIRECTION('center_axis',(-1.,0.,0.));
+#1805=DIRECTION('ref_axis',(0.,0.707106781186547,0.707106781186548));
+#1806=DIRECTION('center_axis',(1.,4.58956396800653E-16,0.));
+#1807=DIRECTION('ref_axis',(0.,0.707106781186547,0.707106781186548));
+#1808=DIRECTION('',(-1.,0.,0.));
+#1809=DIRECTION('center_axis',(-1.,-4.58956396800653E-16,0.));
+#1810=DIRECTION('ref_axis',(0.,0.707106781186547,0.707106781186548));
+#1811=DIRECTION('',(1.,0.,0.));
+#1812=DIRECTION('center_axis',(0.,-1.85037170770859E-16,1.));
+#1813=DIRECTION('ref_axis',(-4.58956396800653E-16,1.,1.85037170770859E-16));
+#1814=DIRECTION('',(-4.58956396800653E-16,1.,1.85037170770859E-16));
+#1815=DIRECTION('',(1.,0.,0.));
+#1816=DIRECTION('',(4.58956396800653E-16,-1.,-1.85037170770859E-16));
+#1817=DIRECTION('center_axis',(-1.,0.,0.));
+#1818=DIRECTION('ref_axis',(0.,0.707106781186546,-0.707106781186549));
+#1819=DIRECTION('center_axis',(1.,4.58956396800653E-16,0.));
+#1820=DIRECTION('ref_axis',(0.,0.707106781186546,-0.707106781186549));
+#1821=DIRECTION('',(-1.,0.,0.));
+#1822=DIRECTION('center_axis',(-1.,-4.58956396800653E-16,0.));
+#1823=DIRECTION('ref_axis',(0.,0.707106781186546,-0.707106781186549));
+#1824=DIRECTION('',(1.,0.,0.));
+#1825=DIRECTION('center_axis',(0.,1.,0.));
+#1826=DIRECTION('ref_axis',(0.,0.,-1.));
+#1827=DIRECTION('',(0.,0.,1.));
+#1828=DIRECTION('',(0.,0.,-1.));
+#1829=DIRECTION('center_axis',(-1.,0.,0.));
+#1830=DIRECTION('ref_axis',(0.,-0.707106781186546,-0.707106781186549));
+#1831=DIRECTION('center_axis',(1.,4.58956396800653E-16,0.));
+#1832=DIRECTION('ref_axis',(0.,-0.707106781186546,-0.707106781186549));
+#1833=DIRECTION('',(-1.,0.,0.));
+#1834=DIRECTION('center_axis',(-1.,-4.58956396800653E-16,0.));
+#1835=DIRECTION('ref_axis',(0.,-0.707106781186546,-0.707106781186549));
+#1836=DIRECTION('',(1.,0.,0.));
+#1837=DIRECTION('center_axis',(0.,1.38777878078145E-16,-1.));
+#1838=DIRECTION('ref_axis',(4.58956396800653E-16,-1.,-1.38777878078145E-16));
+#1839=DIRECTION('',(-4.58956396800653E-16,1.,1.38777878078145E-16));
+#1840=DIRECTION('',(4.58956396800653E-16,-1.,-1.38777878078145E-16));
+#1841=DIRECTION('center_axis',(-1.,0.,0.));
+#1842=DIRECTION('ref_axis',(0.,-0.707106781186546,0.707106781186549));
+#1843=DIRECTION('center_axis',(1.,4.58956396800653E-16,0.));
+#1844=DIRECTION('ref_axis',(0.,-0.707106781186546,0.707106781186549));
+#1845=DIRECTION('',(-1.,0.,0.));
+#1846=DIRECTION('center_axis',(-1.,-4.58956396800653E-16,0.));
+#1847=DIRECTION('ref_axis',(0.,-0.707106781186546,0.707106781186549));
+#1848=DIRECTION('center_axis',(0.,-1.,0.));
+#1849=DIRECTION('ref_axis',(0.,0.,1.));
+#1850=DIRECTION('',(0.,0.,-1.));
+#1851=DIRECTION('',(0.,0.,1.));
+#1852=DIRECTION('center_axis',(-0.408248290463865,-0.408248290463861,-0.816496580927726));
+#1853=DIRECTION('ref_axis',(-0.577350269189627,-0.577350269189625,0.577350269189626));
+#1854=DIRECTION('center_axis',(0.,-1.,0.));
+#1855=DIRECTION('ref_axis',(-1.,0.,0.));
+#1856=DIRECTION('center_axis',(0.,0.,1.));
+#1857=DIRECTION('ref_axis',(0.,-1.,0.));
+#1858=DIRECTION('center_axis',(-1.,0.,0.));
+#1859=DIRECTION('ref_axis',(0.,0.,1.));
+#1860=DIRECTION('center_axis',(0.,0.,1.));
+#1861=DIRECTION('ref_axis',(-0.707106781186549,-0.707106781186546,0.));
+#1862=DIRECTION('center_axis',(0.,0.,1.));
+#1863=DIRECTION('ref_axis',(-0.707106781186549,-0.707106781186546,0.));
+#1864=DIRECTION('',(0.,0.,1.));
+#1865=DIRECTION('',(0.,0.,-1.));
+#1866=DIRECTION('center_axis',(0.408248290463865,-0.40824829046386,-0.816496580927727));
+#1867=DIRECTION('ref_axis',(0.577350269189628,-0.577350269189623,0.577350269189627));
+#1868=DIRECTION('center_axis',(1.,0.,0.));
+#1869=DIRECTION('ref_axis',(0.,-1.,0.));
+#1870=DIRECTION('center_axis',(0.,0.,1.));
+#1871=DIRECTION('ref_axis',(1.,0.,0.));
+#1872=DIRECTION('center_axis',(0.,-1.,0.));
+#1873=DIRECTION('ref_axis',(0.,0.,1.));
+#1874=DIRECTION('center_axis',(0.,0.,1.));
+#1875=DIRECTION('ref_axis',(0.707106781186549,-0.707106781186546,0.));
+#1876=DIRECTION('center_axis',(0.,0.,1.));
+#1877=DIRECTION('ref_axis',(0.707106781186549,-0.707106781186546,0.));
+#1878=DIRECTION('',(0.,0.,1.));
+#1879=DIRECTION('',(0.,0.,-1.));
+#1880=DIRECTION('center_axis',(0.,0.,-1.));
+#1881=DIRECTION('ref_axis',(-1.,0.,0.));
+#1882=DIRECTION('center_axis',(-0.986486625343148,0.163841807909606,0.));
+#1883=DIRECTION('ref_axis',(-0.163841807909606,-0.986486625343148,0.));
+#1884=DIRECTION('center_axis',(0.,0.,-1.));
+#1885=DIRECTION('ref_axis',(0.762837403353299,0.646590361856095,0.));
+#1886=DIRECTION('center_axis',(0.,-1.,0.));
+#1887=DIRECTION('ref_axis',(0.,0.,1.));
+#1888=DIRECTION('center_axis',(0.,0.,1.));
+#1889=DIRECTION('ref_axis',(0.762837403353294,0.646590361856102,0.));
+#1890=DIRECTION('center_axis',(0.,0.,-1.));
+#1891=DIRECTION('ref_axis',(0.762837403353294,0.646590361856102,0.));
+#1892=DIRECTION('',(0.,0.,1.));
+#1893=DIRECTION('',(0.,0.,-1.));
+#1894=DIRECTION('center_axis',(0.,-1.,0.));
+#1895=DIRECTION('ref_axis',(-0.707106781186548,0.,0.707106781186547));
+#1896=DIRECTION('',(0.,-1.,0.));
+#1897=DIRECTION('center_axis',(0.,0.,-1.));
+#1898=DIRECTION('ref_axis',(-1.,0.,0.));
+#1899=DIRECTION('center_axis',(0.,-1.,0.));
+#1900=DIRECTION('ref_axis',(1.,0.,0.));
+#1901=DIRECTION('center_axis',(0.,0.,-1.));
+#1902=DIRECTION('ref_axis',(-0.762837403353299,0.646590361856096,0.));
+#1903=DIRECTION('center_axis',(0.986486625343148,0.163841807909604,0.));
+#1904=DIRECTION('ref_axis',(0.,0.,1.));
+#1905=DIRECTION('center_axis',(0.,0.,1.));
+#1906=DIRECTION('ref_axis',(-0.762837403353305,0.646590361856088,0.));
+#1907=DIRECTION('center_axis',(0.,0.,-1.));
+#1908=DIRECTION('ref_axis',(-0.762837403353305,0.646590361856088,0.));
+#1909=DIRECTION('',(0.,0.,1.));
+#1910=DIRECTION('',(0.,0.,-1.));
+#1911=DIRECTION('center_axis',(0.,0.,1.));
+#1912=DIRECTION('ref_axis',(1.,0.,0.));
+#1913=DIRECTION('center_axis',(-0.931540978723597,-0.363636363636371,0.));
+#1914=DIRECTION('ref_axis',(0.363636363636371,-0.931540978723597,0.));
+#1915=DIRECTION('center_axis',(0.,0.,1.));
+#1916=DIRECTION('ref_axis',(0.260496577422837,-0.96547477085162,0.));
+#1917=DIRECTION('center_axis',(0.,0.,1.));
+#1918=DIRECTION('ref_axis',(1.,0.,0.));
+#1919=DIRECTION('center_axis',(0.,0.,1.));
+#1920=DIRECTION('ref_axis',(0.82572282384477,-0.564076074817767,0.));
+#1921=DIRECTION('center_axis',(0.,-1.,0.));
+#1922=DIRECTION('ref_axis',(1.,0.,0.));
+#1923=DIRECTION('center_axis',(-4.58956396800653E-16,1.,0.));
+#1924=DIRECTION('ref_axis',(0.70710678118655,0.,0.707106781186545));
+#1925=DIRECTION('center_axis',(0.,-1.,0.));
+#1926=DIRECTION('ref_axis',(1.,0.,0.));
+#1927=DIRECTION('',(-4.58956396800653E-16,1.,0.));
+#1928=DIRECTION('center_axis',(0.,0.,1.));
+#1929=DIRECTION('ref_axis',(1.,0.,0.));
+#1930=DIRECTION('center_axis',(0.,0.,1.));
+#1931=DIRECTION('ref_axis',(0.581238193719097,0.813733471206734,0.));
+#1932=DIRECTION('center_axis',(0.945945945945947,0.324324324324322,0.));
+#1933=DIRECTION('ref_axis',(-0.324324324324322,0.945945945945947,0.));
+#1934=DIRECTION('center_axis',(0.,0.,-1.));
+#1935=DIRECTION('ref_axis',(-1.,0.,0.));
+#1936=DIRECTION('center_axis',(0.945945945945948,-0.324324324324318,0.));
+#1937=DIRECTION('ref_axis',(0.324324324324318,0.945945945945948,0.));
+#1938=DIRECTION('center_axis',(0.,0.,-1.));
+#1939=DIRECTION('ref_axis',(1.23710565601088E-16,-1.,0.));
+#1940=DIRECTION('center_axis',(0.,0.,1.));
+#1941=DIRECTION('ref_axis',(1.,0.,0.));
+#1942=DIRECTION('center_axis',(0.,0.,1.));
+#1943=DIRECTION('ref_axis',(-0.581238193719097,0.813733471206735,0.));
+#1944=DIRECTION('center_axis',(0.,1.,0.));
+#1945=DIRECTION('ref_axis',(-1.,0.,0.));
+#1946=DIRECTION('center_axis',(-9.17912793601306E-16,-1.,0.));
+#1947=DIRECTION('ref_axis',(-0.707106781186547,0.,0.707106781186548));
+#1948=DIRECTION('center_axis',(0.,1.,0.));
+#1949=DIRECTION('ref_axis',(-1.,0.,0.));
+#1950=DIRECTION('',(-9.17912793601306E-16,-1.,0.));
+#1951=DIRECTION('center_axis',(0.,0.,1.));
+#1952=DIRECTION('ref_axis',(1.,0.,0.));
+#1953=DIRECTION('center_axis',(0.,0.,1.));
+#1954=DIRECTION('ref_axis',(-0.825722823844769,-0.564076074817768,0.));
+#1955=DIRECTION('center_axis',(-0.931540978723601,0.36363636363636,0.));
+#1956=DIRECTION('ref_axis',(-0.36363636363636,-0.931540978723601,0.));
+#1957=DIRECTION('center_axis',(0.,0.,1.));
+#1958=DIRECTION('ref_axis',(1.,0.,0.));
+#1959=DIRECTION('center_axis',(0.,0.,1.));
+#1960=DIRECTION('ref_axis',(-0.260496577422837,-0.96547477085162,0.));
+#1961=DIRECTION('center_axis',(0.,1.,0.));
+#1962=DIRECTION('ref_axis',(0.707106781186548,0.,0.707106781186547));
+#1963=DIRECTION('',(0.,1.,0.));
+#1964=DIRECTION('center_axis',(1.,0.,0.));
+#1965=DIRECTION('ref_axis',(0.,-0.707106781186547,0.707106781186548));
+#1966=DIRECTION('',(1.,0.,0.));
+#1967=DIRECTION('center_axis',(0.,0.,1.));
+#1968=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#1969=DIRECTION('',(0.,0.,1.));
+#1970=DIRECTION('center_axis',(0.,0.,1.));
+#1971=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#1972=DIRECTION('center_axis',(0.,0.,1.));
+#1973=DIRECTION('ref_axis',(-1.,0.,0.));
+#1974=DIRECTION('',(0.,0.,1.));
+#1975=DIRECTION('center_axis',(0.,0.,1.));
+#1976=DIRECTION('ref_axis',(-1.,0.,0.));
+#1977=DIRECTION('',(0.,0.,1.));
+#1978=DIRECTION('center_axis',(0.,0.,1.));
+#1979=DIRECTION('ref_axis',(-1.,0.,0.));
+#1980=DIRECTION('',(0.,0.,-1.));
+#1981=DIRECTION('center_axis',(0.,0.,1.));
+#1982=DIRECTION('ref_axis',(-1.,0.,0.));
+#1983=DIRECTION('center_axis',(-1.,9.17912793601306E-16,0.));
+#1984=DIRECTION('ref_axis',(-9.17912793601306E-16,-1.,0.));
+#1985=DIRECTION('',(0.,0.,1.));
+#1986=DIRECTION('',(-9.17912793601306E-16,-1.,0.));
+#1987=DIRECTION('center_axis',(0.,0.,1.));
+#1988=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#1989=DIRECTION('',(0.,0.,1.));
+#1990=DIRECTION('center_axis',(0.,0.,1.));
+#1991=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#1992=DIRECTION('',(0.,0.,1.));
+#1993=DIRECTION('center_axis',(0.,0.,1.));
+#1994=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#1995=DIRECTION('',(0.,0.,-1.));
+#1996=DIRECTION('center_axis',(0.,0.,1.));
+#1997=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#1998=DIRECTION('center_axis',(0.,0.,1.));
+#1999=DIRECTION('ref_axis',(-1.22464679914735E-16,-1.,0.));
+#2000=DIRECTION('',(0.,0.,1.));
+#2001=DIRECTION('center_axis',(0.,0.,-1.));
+#2002=DIRECTION('ref_axis',(0.,1.,0.));
+#2003=DIRECTION('center_axis',(0.,0.,1.));
+#2004=DIRECTION('ref_axis',(1.,0.,0.));
+#2005=DIRECTION('',(0.,0.,1.));
+#2006=DIRECTION('center_axis',(0.,0.,1.));
+#2007=DIRECTION('ref_axis',(1.,0.,0.));
+#2008=DIRECTION('',(0.,0.,1.));
+#2009=DIRECTION('center_axis',(0.,0.,1.));
+#2010=DIRECTION('ref_axis',(1.,0.,0.));
+#2011=DIRECTION('',(0.,0.,-1.));
+#2012=DIRECTION('center_axis',(0.,0.,1.));
+#2013=DIRECTION('ref_axis',(1.,0.,0.));
+#2014=DIRECTION('center_axis',(1.,4.58956396800653E-16,0.));
+#2015=DIRECTION('ref_axis',(-4.58956396800653E-16,1.,0.));
+#2016=DIRECTION('',(0.,0.,1.));
+#2017=DIRECTION('',(-4.58956396800653E-16,1.,0.));
+#2018=DIRECTION('center_axis',(0.,0.,1.));
+#2019=DIRECTION('ref_axis',(0.36363636363636,-0.931540978723601,0.));
+#2020=DIRECTION('',(0.,0.,1.));
+#2021=DIRECTION('center_axis',(0.,0.,1.));
+#2022=DIRECTION('ref_axis',(0.36363636363636,-0.931540978723601,0.));
+#2023=DIRECTION('',(0.,0.,1.));
+#2024=DIRECTION('center_axis',(0.,0.,1.));
+#2025=DIRECTION('ref_axis',(0.36363636363636,-0.931540978723601,0.));
+#2026=DIRECTION('',(0.,0.,-1.));
+#2027=DIRECTION('center_axis',(0.,0.,1.));
+#2028=DIRECTION('ref_axis',(0.36363636363636,-0.931540978723601,0.));
+#2029=DIRECTION('center_axis',(0.,0.,1.));
+#2030=DIRECTION('ref_axis',(-1.01506105108586E-16,-1.,0.));
+#2031=DIRECTION('center_axis',(0.,0.,1.));
+#2032=DIRECTION('ref_axis',(-1.01506105108586E-16,-1.,0.));
+#2033=DIRECTION('center_axis',(0.,1.,0.));
+#2034=DIRECTION('ref_axis',(1.,0.,0.));
+#2035=DIRECTION('',(0.,1.,0.));
+#2036=DIRECTION('center_axis',(0.,1.,0.));
+#2037=DIRECTION('ref_axis',(1.,0.,0.));
+#2038=DIRECTION('',(0.,-1.,0.));
+#2039=DIRECTION('center_axis',(0.,-1.,0.));
+#2040=DIRECTION('ref_axis',(1.,0.,0.));
+#2041=DIRECTION('center_axis',(0.,1.,0.));
+#2042=DIRECTION('ref_axis',(1.,0.,0.));
+#2043=DIRECTION('',(0.,1.,0.));
+#2044=DIRECTION('center_axis',(0.,1.,0.));
+#2045=DIRECTION('ref_axis',(1.,0.,0.));
+#2046=DIRECTION('',(0.,-1.,0.));
+#2047=DIRECTION('center_axis',(0.,-1.,0.));
+#2048=DIRECTION('ref_axis',(1.,0.,0.));
+#2049=DIRECTION('center_axis',(0.,0.,1.));
+#2050=DIRECTION('ref_axis',(1.,0.,0.));
+#2051=DIRECTION('',(1.,0.,0.));
+#2052=DIRECTION('',(1.,0.,0.));
+#2053=DIRECTION('center_axis',(0.,0.,1.));
+#2054=DIRECTION('ref_axis',(1.,0.,0.));
+#2055=DIRECTION('',(0.,-1.,0.));
+#2056=DIRECTION('center_axis',(0.,0.,-1.));
+#2057=DIRECTION('ref_axis',(-1.,0.,0.));
+#2058=DIRECTION('center_axis',(0.,0.,-1.));
+#2059=DIRECTION('ref_axis',(-1.,0.,0.));
+#2060=DIRECTION('center_axis',(0.,0.,-1.));
+#2061=DIRECTION('ref_axis',(-1.,0.,0.));
+#2062=DIRECTION('center_axis',(0.,0.,-1.));
+#2063=DIRECTION('ref_axis',(-1.,0.,0.));
+#2064=DIRECTION('',(0.,1.,0.));
+#2065=DIRECTION('',(1.,0.,0.));
+#2066=DIRECTION('',(1.,0.,0.));
+#2067=DIRECTION('',(0.,1.,0.));
+#2068=DIRECTION('center_axis',(0.,0.,1.));
+#2069=DIRECTION('ref_axis',(-1.01506105108586E-16,-1.,0.));
+#2070=DIRECTION('center_axis',(0.,0.,-1.));
+#2071=DIRECTION('ref_axis',(-1.,0.,0.));
+#2072=DIRECTION('',(-4.58956396800653E-16,1.,0.));
+#2073=DIRECTION('center_axis',(0.,0.,1.));
+#2074=DIRECTION('ref_axis',(1.,0.,0.));
+#2075=DIRECTION('center_axis',(0.,0.,-1.));
+#2076=DIRECTION('ref_axis',(-1.,0.,0.));
+#2077=DIRECTION('center_axis',(0.,0.,1.));
+#2078=DIRECTION('ref_axis',(1.,0.,0.));
+#2079=DIRECTION('center_axis',(0.,0.,-1.));
+#2080=DIRECTION('ref_axis',(0.,1.,0.));
+#2081=DIRECTION('center_axis',(0.,0.,1.));
+#2082=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#2083=DIRECTION('center_axis',(0.,0.,-1.));
+#2084=DIRECTION('ref_axis',(-1.,0.,0.));
+#2085=DIRECTION('center_axis',(0.,0.,1.));
+#2086=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#2087=DIRECTION('',(-9.17912793601306E-16,-1.,0.));
+#2088=DIRECTION('center_axis',(0.,0.,-1.));
+#2089=DIRECTION('ref_axis',(-1.,0.,0.));
+#2090=DIRECTION('center_axis',(0.,0.,1.));
+#2091=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#2092=DIRECTION('',(0.,-1.,0.));
+#2093=DIRECTION('',(1.,0.,0.));
+#2094=DIRECTION('',(1.,0.,0.));
+#2095=DIRECTION('center_axis',(0.,0.,1.));
+#2096=DIRECTION('ref_axis',(-1.,0.,0.));
+#2097=DIRECTION('center_axis',(0.,0.,1.));
+#2098=DIRECTION('ref_axis',(-1.,0.,0.));
+#2099=DIRECTION('center_axis',(0.,0.,1.));
+#2100=DIRECTION('ref_axis',(-1.,0.,0.));
+#2101=DIRECTION('center_axis',(0.,0.,1.));
+#2102=DIRECTION('ref_axis',(-1.,0.,0.));
+#2103=DIRECTION('center_axis',(0.,-1.,0.));
+#2104=DIRECTION('ref_axis',(1.,0.,0.));
+#2105=DIRECTION('',(0.,0.,-1.));
+#2106=DIRECTION('',(-1.,0.,0.));
+#2107=DIRECTION('',(0.,0.,-1.));
+#2108=DIRECTION('center_axis',(0.,0.,1.));
+#2109=DIRECTION('ref_axis',(-1.,0.,0.));
+#2110=DIRECTION('',(0.,0.,1.));
+#2111=DIRECTION('center_axis',(0.,0.,1.));
+#2112=DIRECTION('ref_axis',(-1.,0.,0.));
+#2113=DIRECTION('',(0.,0.,1.));
+#2114=DIRECTION('center_axis',(0.,0.,1.));
+#2115=DIRECTION('ref_axis',(-1.,0.,0.));
+#2116=DIRECTION('',(0.,0.,1.));
+#2117=DIRECTION('center_axis',(0.,0.,1.));
+#2118=DIRECTION('ref_axis',(-1.,0.,0.));
+#2119=DIRECTION('',(0.,0.,1.));
+#2120=DIRECTION('center_axis',(0.,0.,-1.));
+#2121=DIRECTION('ref_axis',(-1.,0.,0.));
+#2122=DIRECTION('center_axis',(0.,0.,-1.));
+#2123=DIRECTION('ref_axis',(-1.,0.,0.));
+#2124=DIRECTION('center_axis',(0.,0.,-1.));
+#2125=DIRECTION('ref_axis',(-1.,0.,0.));
+#2126=DIRECTION('center_axis',(0.,0.,-1.));
+#2127=DIRECTION('ref_axis',(-1.,0.,0.));
+#2128=DIRECTION('',(0.,0.,1.));
+#2129=DIRECTION('',(0.,0.,-1.));
+#2130=DIRECTION('center_axis',(0.,0.,1.));
+#2131=DIRECTION('ref_axis',(-1.,0.,0.));
+#2132=DIRECTION('center_axis',(0.,0.,-1.));
+#2133=DIRECTION('ref_axis',(-1.,0.,0.));
+#2134=DIRECTION('center_axis',(0.,0.,-1.));
+#2135=DIRECTION('ref_axis',(-1.,0.,0.));
+#2136=DIRECTION('center_axis',(0.,0.,-1.));
+#2137=DIRECTION('ref_axis',(0.8377151377058,0.546107451019076,0.));
+#2138=DIRECTION('',(0.,0.,1.));
+#2139=DIRECTION('',(0.,0.,-1.));
+#2140=DIRECTION('center_axis',(0.,0.,1.));
+#2141=DIRECTION('ref_axis',(-1.,0.,0.));
+#2142=DIRECTION('center_axis',(0.,0.,-1.));
+#2143=DIRECTION('ref_axis',(-1.,0.,0.));
+#2144=DIRECTION('center_axis',(0.,0.,-1.));
+#2145=DIRECTION('ref_axis',(-1.,0.,0.));
+#2146=DIRECTION('center_axis',(0.,0.,-1.));
+#2147=DIRECTION('ref_axis',(-1.,0.,0.));
+#2148=DIRECTION('center_axis',(0.,0.,-1.));
+#2149=DIRECTION('ref_axis',(-1.,0.,0.));
+#2150=DIRECTION('center_axis',(0.,0.,-1.));
+#2151=DIRECTION('ref_axis',(-1.,0.,0.));
+#2152=DIRECTION('',(0.,0.,-1.));
+#2153=DIRECTION('center_axis',(0.,0.,1.));
+#2154=DIRECTION('ref_axis',(-1.,0.,0.));
+#2155=DIRECTION('',(0.,0.,1.));
+#2156=DIRECTION('center_axis',(0.,0.,-1.));
+#2157=DIRECTION('ref_axis',(-1.,0.,0.));
+#2158=DIRECTION('center_axis',(0.,0.,-1.));
+#2159=DIRECTION('ref_axis',(-1.,0.,0.));
+#2160=DIRECTION('center_axis',(0.,0.,-1.));
+#2161=DIRECTION('ref_axis',(0.599044881228425,-0.800715449004216,0.));
+#2162=DIRECTION('',(0.,0.,1.));
+#2163=DIRECTION('',(0.,0.,-1.));
+#2164=DIRECTION('center_axis',(0.,0.,1.));
+#2165=DIRECTION('ref_axis',(-1.,0.,0.));
+#2166=DIRECTION('center_axis',(0.,0.,-1.));
+#2167=DIRECTION('ref_axis',(-1.,0.,0.));
+#2168=DIRECTION('center_axis',(0.,0.,1.));
+#2169=DIRECTION('ref_axis',(-1.01506105108586E-16,-1.,0.));
+#2170=DIRECTION('',(0.,0.,1.));
+#2171=DIRECTION('center_axis',(0.,0.,-1.));
+#2172=DIRECTION('ref_axis',(-1.01506105108586E-16,-1.,0.));
+#2173=DIRECTION('center_axis',(-1.,9.17912793601306E-16,0.));
+#2174=DIRECTION('ref_axis',(-9.17912793601306E-16,-1.,0.));
+#2175=DIRECTION('',(0.,0.,1.));
+#2176=DIRECTION('',(9.17912793601306E-16,1.,0.));
+#2177=DIRECTION('center_axis',(0.,0.,1.));
+#2178=DIRECTION('ref_axis',(1.,0.,0.));
+#2179=DIRECTION('center_axis',(0.,0.,-1.));
+#2180=DIRECTION('ref_axis',(1.,0.,0.));
+#2181=DIRECTION('',(0.,0.,1.));
+#2182=DIRECTION('center_axis',(0.,0.,1.));
+#2183=DIRECTION('ref_axis',(1.,0.,0.));
+#2184=DIRECTION('',(0.,0.,1.));
+#2185=DIRECTION('center_axis',(0.,0.,-1.));
+#2186=DIRECTION('ref_axis',(1.,0.,0.));
+#2187=DIRECTION('center_axis',(0.,0.,1.));
+#2188=DIRECTION('ref_axis',(1.,0.,0.));
+#2189=DIRECTION('',(0.,-1.,0.));
+#2190=DIRECTION('',(0.,1.,0.));
+#2191=DIRECTION('center_axis',(0.,0.,-1.));
+#2192=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#2193=DIRECTION('center_axis',(0.,0.,-1.));
+#2194=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#2195=DIRECTION('center_axis',(0.,0.,-1.));
+#2196=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#2197=DIRECTION('center_axis',(0.,0.,1.));
+#2198=DIRECTION('ref_axis',(0.,1.,0.));
+#2199=DIRECTION('',(4.58956396800653E-16,-1.,0.));
+#2200=DIRECTION('center_axis',(0.,0.,1.));
+#2201=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#2202=DIRECTION('',(0.,0.,1.));
+#2203=DIRECTION('center_axis',(0.,0.,1.));
+#2204=DIRECTION('ref_axis',(0.324324324324324,0.945945945945946,0.));
+#2205=DIRECTION('center_axis',(0.,0.,1.));
+#2206=DIRECTION('ref_axis',(-1.22464679914735E-16,-1.,0.));
+#2207=DIRECTION('center_axis',(1.,4.58956396800653E-16,0.));
+#2208=DIRECTION('ref_axis',(-4.58956396800653E-16,1.,0.));
+#2209=DIRECTION('center_axis',(1.,0.,0.));
+#2210=DIRECTION('ref_axis',(0.,1.,0.));
+#2211=DIRECTION('center_axis',(-1.,0.,0.));
+#2212=DIRECTION('ref_axis',(0.,-1.,0.));
+#2213=DIRECTION('',(0.,0.,1.));
+#2214=DIRECTION('center_axis',(0.,0.,1.));
+#2215=DIRECTION('ref_axis',(-0.363636363636363,-0.9315409787236,0.));
+#2216=DIRECTION('center_axis',(1.,0.,0.));
+#2217=DIRECTION('ref_axis',(0.,1.,0.));
+#2218=DIRECTION('center_axis',(0.,-1.,0.));
+#2219=DIRECTION('ref_axis',(1.,0.,0.));
+#2220=DIRECTION('center_axis',(-1.,0.,0.));
+#2221=DIRECTION('ref_axis',(0.,-1.,0.));
+#2222=CARTESIAN_POINT('',(0.,0.,0.));
+#2223=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,17.));
+#2224=CARTESIAN_POINT('',(-69.5708994594568,-124.35436527946,17.));
+#2225=CARTESIAN_POINT('',(-72.7331134995567,-120.650717393207,16.9569974716148));
+#2226=CARTESIAN_POINT('Ctrl Pts',(-69.5708994594568,-124.35436527946,17.));
+#2227=CARTESIAN_POINT('Ctrl Pts',(-69.7506659325307,-124.325835513084,17.));
+#2228=CARTESIAN_POINT('Ctrl Pts',(-69.9317074555371,-124.283694916792,16.9945513125405));
+#2229=CARTESIAN_POINT('Ctrl Pts',(-70.5541832401233,-124.087138851083,16.9638753227374));
+#2230=CARTESIAN_POINT('Ctrl Pts',(-70.9665910676917,-123.866955508681,16.9239695626842));
+#2231=CARTESIAN_POINT('Ctrl Pts',(-71.6973839554848,-123.280949974723,16.864967897657));
+#2232=CARTESIAN_POINT('Ctrl Pts',(-72.0068177253728,-122.918827230534,16.8475970530855));
+#2233=CARTESIAN_POINT('Ctrl Pts',(-72.485214405272,-122.079121036881,16.8587049916568));
+#2234=CARTESIAN_POINT('Ctrl Pts',(-72.6415718692489,-121.608851771295,16.8887710693201));
+#2235=CARTESIAN_POINT('Ctrl Pts',(-72.7233417615952,-120.964780013456,16.9349630740485));
+#2236=CARTESIAN_POINT('Ctrl Pts',(-72.7331134995567,-120.807046574789,16.946461353126));
+#2237=CARTESIAN_POINT('Ctrl Pts',(-72.7331134995567,-120.650717393208,16.9569974716148));
+#2238=CARTESIAN_POINT('',(-72.5884592110254,-119.619222215907,17.));
+#2239=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,17.));
+#2240=CARTESIAN_POINT('Ctrl Pts',(-72.7331134995567,-120.650717393208,16.9569974716148));
+#2241=CARTESIAN_POINT('Ctrl Pts',(-72.7331134995567,-120.319393350159,16.9793277194956));
+#2242=CARTESIAN_POINT('Ctrl Pts',(-72.6891620156092,-119.994384833065,16.9974521249162));
+#2243=CARTESIAN_POINT('Ctrl Pts',(-72.6006068347402,-119.662410744818,16.9999174664142));
+#2244=CARTESIAN_POINT('Ctrl Pts',(-72.594619672589,-119.640754642008,17.));
+#2245=CARTESIAN_POINT('Ctrl Pts',(-72.5884592110254,-119.619222215907,17.));
+#2246=CARTESIAN_POINT('',(-72.7331134995567,-120.650717393207,13.));
+#2247=CARTESIAN_POINT('',(-72.7331134995567,-120.650717393207,17.));
+#2248=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,13.));
+#2249=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,13.));
+#2250=CARTESIAN_POINT('',(-66.4831134995567,-120.650717393207,13.));
+#2251=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,13.));
+#2252=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,17.));
+#2253=CARTESIAN_POINT('',(57.4810069175821,-71.5775608194672,17.));
+#2254=CARTESIAN_POINT('',(61.9712688757706,-74.936892083492,17.));
+#2255=CARTESIAN_POINT('Ctrl Pts',(57.4810069175821,-71.5775608194672,17.));
+#2256=CARTESIAN_POINT('Ctrl Pts',(57.83195494648,-71.5055807079621,17.));
+#2257=CARTESIAN_POINT('Ctrl Pts',(58.1922774854578,-71.4841294111555,16.9795116352103));
+#2258=CARTESIAN_POINT('Ctrl Pts',(58.9566535105112,-71.5487883719186,16.9275449890312));
+#2259=CARTESIAN_POINT('Ctrl Pts',(59.3553893905851,-71.6492586946785,16.8954623408113));
+#2260=CARTESIAN_POINT('Ctrl Pts',(59.9478863124396,-71.9069997196861,16.8637969293796));
+#2261=CARTESIAN_POINT('Ctrl Pts',(60.1559777149514,-72.0220505870076,16.856160641822));
+#2262=CARTESIAN_POINT('Ctrl Pts',(60.5299112779413,-72.2779062076078,16.8517319299727));
+#2263=CARTESIAN_POINT('Ctrl Pts',(60.6967774202217,-72.4145660705293,16.8539963606755));
+#2264=CARTESIAN_POINT('Ctrl Pts',(61.0598466294315,-72.7682288945721,16.868847267708));
+#2265=CARTESIAN_POINT('Ctrl Pts',(61.2438515089492,-72.9948639583803,16.8848149293476));
+#2266=CARTESIAN_POINT('Ctrl Pts',(61.6638407981144,-73.6559797308266,16.9366750515163));
+#2267=CARTESIAN_POINT('Ctrl Pts',(61.8429547790174,-74.1186418156355,16.9788624125823));
+#2268=CARTESIAN_POINT('Ctrl Pts',(61.9476494870036,-74.7147167544218,16.9979819762427));
+#2269=CARTESIAN_POINT('Ctrl Pts',(61.9619734662679,-74.8263400394601,17.));
+#2270=CARTESIAN_POINT('Ctrl Pts',(61.9712688757706,-74.936892083492,17.));
+#2271=CARTESIAN_POINT('',(54.4844547654759,-75.2510899592052,17.));
+#2272=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,17.));
+#2273=CARTESIAN_POINT('',(54.4844547654759,-75.2510899592052,13.));
+#2274=CARTESIAN_POINT('',(54.4844547654759,-75.2510899592052,17.));
+#2275=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,13.));
+#2276=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,17.));
+#2277=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,13.));
+#2278=CARTESIAN_POINT('',(60.7344547654759,-75.2510899592052,13.));
+#2279=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,13.));
+#2280=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,17.));
+#2281=CARTESIAN_POINT('',(-71.4957249213666,-74.9368920834921,17.));
+#2282=CARTESIAN_POINT('',(-67.0054629631782,-71.5775608194672,17.));
+#2283=CARTESIAN_POINT('Ctrl Pts',(-71.4957249213666,-74.9368920834921,17.));
+#2284=CARTESIAN_POINT('Ctrl Pts',(-71.4657082477618,-74.5798981693349,17.));
+#2285=CARTESIAN_POINT('Ctrl Pts',(-71.384571483018,-74.2281748183372,16.9795116352103));
+#2286=CARTESIAN_POINT('Ctrl Pts',(-71.1067662078617,-73.5131393520989,16.9275449890312));
+#2287=CARTESIAN_POINT('Ctrl Pts',(-70.8978227801748,-73.1589822798269,16.8954623408113));
+#2288=CARTESIAN_POINT('Ctrl Pts',(-70.4833081160671,-72.6633406435426,16.8637969293796));
+#2289=CARTESIAN_POINT('Ctrl Pts',(-70.3141942667795,-72.4961902925112,16.856160641822));
+#2290=CARTESIAN_POINT('Ctrl Pts',(-69.9631866769955,-72.2096905891307,16.8517319299727));
+#2291=CARTESIAN_POINT('Ctrl Pts',(-69.7849801896518,-72.0881888383536,16.8539963606755));
+#2292=CARTESIAN_POINT('Ctrl Pts',(-69.34321021838,-71.8397216649308,16.868847267708));
+#2293=CARTESIAN_POINT('Ctrl Pts',(-69.0738498111283,-71.7271773677017,16.8848149293476));
+#2294=CARTESIAN_POINT('Ctrl Pts',(-68.321063320238,-71.5108961463163,16.9366750515163));
+#2295=CARTESIAN_POINT('Ctrl Pts',(-67.8266560052056,-71.4696720063369,16.9788624125823));
+#2296=CARTESIAN_POINT('Ctrl Pts',(-67.2252697235942,-71.5375016076851,16.9979819762427));
+#2297=CARTESIAN_POINT('Ctrl Pts',(-67.1141427484772,-71.5552703877792,17.));
+#2298=CARTESIAN_POINT('Ctrl Pts',(-67.0054629631782,-71.5775608194672,17.));
+#2299=CARTESIAN_POINT('',(-71.508910811072,-75.2510899592052,17.));
+#2300=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,17.));
+#2301=CARTESIAN_POINT('',(-71.508910811072,-75.2510899592052,13.));
+#2302=CARTESIAN_POINT('',(-71.508910811072,-75.2510899592052,17.));
+#2303=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,13.));
+#2304=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,17.));
+#2305=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,13.));
+#2306=CARTESIAN_POINT('',(-65.258910811072,-75.2510899592052,13.));
+#2307=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,13.));
+#2308=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,17.));
+#2309=CARTESIAN_POINT('',(63.0640031654294,-119.619222215907,17.));
+#2310=CARTESIAN_POINT('',(60.0464434138608,-124.35436527946,17.));
+#2311=CARTESIAN_POINT('Ctrl Pts',(63.0640031654294,-119.619222215907,17.));
+#2312=CARTESIAN_POINT('Ctrl Pts',(63.1346084275147,-119.866006092815,17.));
+#2313=CARTESIAN_POINT('Ctrl Pts',(63.1814202768092,-120.125384299052,16.989183269613));
+#2314=CARTESIAN_POINT('Ctrl Pts',(63.231540055038,-120.855492253484,16.9460798644208));
+#2315=CARTESIAN_POINT('Ctrl Pts',(63.1777017238941,-121.319128012286,16.9065932119511));
+#2316=CARTESIAN_POINT('Ctrl Pts',(62.8981531311864,-122.219606539607,16.8549190443895));
+#2317=CARTESIAN_POINT('Ctrl Pts',(62.6705899988847,-122.644732937923,16.8451166103254));
+#2318=CARTESIAN_POINT('Ctrl Pts',(62.0557216422575,-123.40072801532,16.8707467323269));
+#2319=CARTESIAN_POINT('Ctrl Pts',(61.6714300198972,-123.717991496282,16.9068630963351));
+#2320=CARTESIAN_POINT('Ctrl Pts',(60.8569507823189,-124.157151354207,16.9725240310507));
+#2321=CARTESIAN_POINT('Ctrl Pts',(60.4525939472996,-124.289907321119,17.));
+#2322=CARTESIAN_POINT('Ctrl Pts',(60.0464434138608,-124.35436527946,17.));
+#2323=CARTESIAN_POINT('',(55.7086574539607,-120.650717393207,17.));
+#2324=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,17.));
+#2325=CARTESIAN_POINT('',(55.7086574539607,-120.650717393207,13.));
+#2326=CARTESIAN_POINT('',(55.7086574539607,-120.650717393207,17.));
+#2327=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,13.));
+#2328=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,17.));
+#2329=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,13.));
+#2330=CARTESIAN_POINT('',(61.9586574539607,-120.650717393207,13.));
+#2331=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,13.));
+#2332=CARTESIAN_POINT('Origin',(-4.76222802279802,-105.756616555836,17.));
+#2333=CARTESIAN_POINT('',(-67.6713189318889,-125.413205875019,17.));
+#2334=CARTESIAN_POINT('Origin',(-64.762228022798,-117.96087804523,17.));
+#2335=CARTESIAN_POINT('',(-33.1068607911596,-134.918802740201,17.));
+#2336=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,17.));
+#2337=CARTESIAN_POINT('',(-29.762228022798,-138.864749241573,17.));
+#2338=CARTESIAN_POINT('Origin',(-33.762228022798,-138.864749241573,17.));
+#2339=CARTESIAN_POINT('',(-29.762228022798,-140.256616555836,17.));
+#2340=CARTESIAN_POINT('',(-29.762228022798,-121.45891554204,17.));
+#2341=CARTESIAN_POINT('',(20.237771977202,-140.256616555836,17.));
+#2342=CARTESIAN_POINT('',(-18.262228022798,-140.256616555836,17.));
+#2343=CARTESIAN_POINT('',(20.237771977202,-138.864749241573,17.));
+#2344=CARTESIAN_POINT('',(20.237771977202,-124.006616555836,17.));
+#2345=CARTESIAN_POINT('',(23.5824047455636,-134.918802740201,17.));
+#2346=CARTESIAN_POINT('Origin',(24.237771977202,-138.864749241573,17.));
+#2347=CARTESIAN_POINT('',(58.1468628862929,-125.413205875019,17.));
+#2348=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,17.));
+#2349=CARTESIAN_POINT('Origin',(55.237771977202,-117.96087804523,17.));
+#2350=CARTESIAN_POINT('',(63.237771977202,-117.96087804523,17.));
+#2351=CARTESIAN_POINT('Origin',(55.237771977202,-117.96087804523,17.));
+#2352=CARTESIAN_POINT('',(63.237771977202,-79.256616555836,17.));
+#2353=CARTESIAN_POINT('',(63.237771977202,-111.858747300533,17.));
+#2354=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,17.));
+#2355=CARTESIAN_POINT('',(52.6431773826074,-71.6890489882684,17.));
+#2356=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,17.));
+#2357=CARTESIAN_POINT('',(-62.1676334282034,-71.6890489882684,17.));
+#2358=CARTESIAN_POINT('Origin',(-4.76222802279802,95.7433834441657,17.));
+#2359=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,17.));
+#2360=CARTESIAN_POINT('',(-72.762228022798,-79.256616555836,17.));
+#2361=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,17.));
+#2362=CARTESIAN_POINT('',(-72.762228022798,-117.96087804523,17.));
+#2363=CARTESIAN_POINT('',(-72.762228022798,-92.5066165558359,17.));
+#2364=CARTESIAN_POINT('Origin',(-64.762228022798,-117.96087804523,17.));
+#2365=CARTESIAN_POINT('Origin',(65.237771977202,-93.9608780452299,10.));
+#2366=CARTESIAN_POINT('',(65.237771977202,-91.9608780452299,10.));
+#2367=CARTESIAN_POINT('',(65.237771977202,-93.9608780452299,12.));
+#2368=CARTESIAN_POINT('Origin',(65.237771977202,-93.9608780452299,10.));
+#2369=CARTESIAN_POINT('',(62.237771977202,-93.9608780452299,12.));
+#2370=CARTESIAN_POINT('',(65.237771977202,-93.9608780452299,12.));
+#2371=CARTESIAN_POINT('',(62.237771977202,-91.9608780452299,10.));
+#2372=CARTESIAN_POINT('Origin',(62.237771977202,-93.9608780452299,10.));
+#2373=CARTESIAN_POINT('',(65.237771977202,-91.9608780452299,10.));
+#2374=CARTESIAN_POINT('Origin',(65.237771977202,-103.96087804523,12.));
+#2375=CARTESIAN_POINT('',(65.237771977202,-101.96087804523,12.));
+#2376=CARTESIAN_POINT('',(65.237771977202,-110.96087804523,12.));
+#2377=CARTESIAN_POINT('',(62.237771977202,-101.96087804523,12.));
+#2378=CARTESIAN_POINT('',(65.237771977202,-101.96087804523,12.));
+#2379=CARTESIAN_POINT('',(62.237771977202,-110.96087804523,12.));
+#2380=CARTESIAN_POINT('Origin',(65.237771977202,-93.9608780452299,6.));
+#2381=CARTESIAN_POINT('',(65.237771977202,-93.9608780452299,4.));
+#2382=CARTESIAN_POINT('',(65.237771977202,-91.9608780452299,6.));
+#2383=CARTESIAN_POINT('Origin',(65.237771977202,-93.9608780452299,6.));
+#2384=CARTESIAN_POINT('',(62.237771977202,-91.9608780452299,6.));
+#2385=CARTESIAN_POINT('',(65.237771977202,-91.9608780452299,6.));
+#2386=CARTESIAN_POINT('',(62.237771977202,-93.9608780452299,4.));
+#2387=CARTESIAN_POINT('Origin',(62.237771977202,-93.9608780452299,6.));
+#2388=CARTESIAN_POINT('',(65.237771977202,-93.9608780452299,4.));
+#2389=CARTESIAN_POINT('Origin',(65.237771977202,-91.9608780452299,12.));
+#2390=CARTESIAN_POINT('',(62.237771977202,-91.9608780452299,6.));
+#2391=CARTESIAN_POINT('',(65.237771977202,-91.9608780452299,6.));
+#2392=CARTESIAN_POINT('Origin',(65.237771977202,-101.96087804523,6.));
+#2393=CARTESIAN_POINT('',(65.237771977202,-103.96087804523,6.));
+#2394=CARTESIAN_POINT('',(65.237771977202,-101.96087804523,4.));
+#2395=CARTESIAN_POINT('Origin',(65.237771977202,-101.96087804523,6.));
+#2396=CARTESIAN_POINT('',(62.237771977202,-101.96087804523,4.));
+#2397=CARTESIAN_POINT('',(65.237771977202,-101.96087804523,4.));
+#2398=CARTESIAN_POINT('',(62.237771977202,-103.96087804523,6.));
+#2399=CARTESIAN_POINT('Origin',(62.237771977202,-101.96087804523,6.));
+#2400=CARTESIAN_POINT('',(65.237771977202,-103.96087804523,6.));
+#2401=CARTESIAN_POINT('Origin',(65.237771977202,-91.9608780452299,4.));
+#2402=CARTESIAN_POINT('',(62.237771977202,-104.96087804523,4.));
+#2403=CARTESIAN_POINT('',(65.237771977202,-104.96087804523,4.));
+#2404=CARTESIAN_POINT('Origin',(65.237771977202,-101.96087804523,10.));
+#2405=CARTESIAN_POINT('',(65.237771977202,-103.96087804523,10.));
+#2406=CARTESIAN_POINT('Origin',(65.237771977202,-101.96087804523,10.));
+#2407=CARTESIAN_POINT('',(62.237771977202,-103.96087804523,10.));
+#2408=CARTESIAN_POINT('',(65.237771977202,-103.96087804523,10.));
+#2409=CARTESIAN_POINT('Origin',(62.237771977202,-101.96087804523,10.));
+#2410=CARTESIAN_POINT('Origin',(65.237771977202,-103.96087804523,4.));
+#2411=CARTESIAN_POINT('',(62.237771977202,-103.96087804523,2.));
+#2412=CARTESIAN_POINT('',(65.237771977202,-103.96087804523,2.));
+#2413=CARTESIAN_POINT('Origin',(-29.762228022798,-140.256616555836,15.));
+#2414=CARTESIAN_POINT('',(-31.762228022798,-140.256616555836,15.));
+#2415=CARTESIAN_POINT('Origin',(-29.762228022798,-140.256616555836,15.));
+#2416=CARTESIAN_POINT('',(-29.762228022798,-142.256616555836,15.));
+#2417=CARTESIAN_POINT('Origin',(-29.762228022798,-140.256616555836,15.));
+#2418=CARTESIAN_POINT('Origin',(-29.762228022798,-140.256616555836,15.));
+#2419=CARTESIAN_POINT('Origin',(-29.762228022798,-140.256616555836,0.));
+#2420=CARTESIAN_POINT('',(-31.762228022798,-140.256616555836,0.));
+#2421=CARTESIAN_POINT('',(-29.762228022798,-142.256616555836,0.));
+#2422=CARTESIAN_POINT('Origin',(-29.762228022798,-140.256616555836,0.));
+#2423=CARTESIAN_POINT('',(-29.762228022798,-142.256616555836,0.));
+#2424=CARTESIAN_POINT('',(-31.762228022798,-140.256616555836,0.));
+#2425=CARTESIAN_POINT('Origin',(20.237771977202,-140.256616555836,15.));
+#2426=CARTESIAN_POINT('',(20.237771977202,-142.256616555836,15.));
+#2427=CARTESIAN_POINT('Origin',(20.237771977202,-140.256616555836,15.));
+#2428=CARTESIAN_POINT('',(22.237771977202,-140.256616555836,15.));
+#2429=CARTESIAN_POINT('Origin',(20.237771977202,-140.256616555836,15.));
+#2430=CARTESIAN_POINT('Origin',(20.237771977202,-140.256616555836,15.));
+#2431=CARTESIAN_POINT('Origin',(20.237771977202,-140.256616555836,0.));
+#2432=CARTESIAN_POINT('',(20.237771977202,-142.256616555836,0.));
+#2433=CARTESIAN_POINT('',(22.237771977202,-140.256616555836,0.));
+#2434=CARTESIAN_POINT('Origin',(20.237771977202,-140.256616555836,0.));
+#2435=CARTESIAN_POINT('',(22.237771977202,-140.256616555836,0.));
+#2436=CARTESIAN_POINT('',(20.237771977202,-142.256616555836,0.));
+#2437=CARTESIAN_POINT('Origin',(-33.762228022798,-138.864749241573,15.));
+#2438=CARTESIAN_POINT('',(-33.4345444069788,-136.891775990887,15.));
+#2439=CARTESIAN_POINT('Origin',(-33.1068607911596,-134.918802740201,15.));
+#2440=CARTESIAN_POINT('',(-31.762228022798,-138.864749241573,15.));
+#2441=CARTESIAN_POINT('Origin',(-33.762228022798,-138.864749241573,15.));
+#2442=CARTESIAN_POINT('Origin',(-29.762228022798,-138.864749241573,15.));
+#2443=CARTESIAN_POINT('Origin',(-33.762228022798,-138.864749241573,0.));
+#2444=CARTESIAN_POINT('',(-33.4345444069788,-136.891775990887,0.));
+#2445=CARTESIAN_POINT('',(-31.762228022798,-138.864749241573,0.));
+#2446=CARTESIAN_POINT('Origin',(-33.762228022798,-138.864749241573,0.));
+#2447=CARTESIAN_POINT('',(-31.762228022798,-138.864749241573,0.));
+#2448=CARTESIAN_POINT('',(-33.4345444069788,-136.891775990887,0.));
+#2449=CARTESIAN_POINT('Origin',(-29.762228022798,-121.45891554204,15.));
+#2450=CARTESIAN_POINT('',(-31.762228022798,-121.45891554204,15.));
+#2451=CARTESIAN_POINT('Origin',(24.237771977202,-138.864749241573,15.));
+#2452=CARTESIAN_POINT('',(22.237771977202,-138.864749241573,15.));
+#2453=CARTESIAN_POINT('Origin',(20.237771977202,-138.864749241573,15.));
+#2454=CARTESIAN_POINT('',(23.9100883613828,-136.891775990887,15.));
+#2455=CARTESIAN_POINT('Origin',(24.237771977202,-138.864749241573,15.));
+#2456=CARTESIAN_POINT('Origin',(23.5824047455636,-134.918802740201,15.));
+#2457=CARTESIAN_POINT('Origin',(24.237771977202,-138.864749241573,0.));
+#2458=CARTESIAN_POINT('',(22.237771977202,-138.864749241573,0.));
+#2459=CARTESIAN_POINT('',(23.9100883613828,-136.891775990887,0.));
+#2460=CARTESIAN_POINT('Origin',(24.237771977202,-138.864749241573,0.));
+#2461=CARTESIAN_POINT('',(23.9100883613828,-136.891775990887,0.));
+#2462=CARTESIAN_POINT('',(22.237771977202,-138.864749241573,0.));
+#2463=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,15.));
+#2464=CARTESIAN_POINT('',(58.8741356135656,-127.276287832466,15.));
+#2465=CARTESIAN_POINT('Origin',(58.1468628862929,-125.413205875019,15.));
+#2466=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,15.));
+#2467=CARTESIAN_POINT('Origin',(55.237771977202,-117.96087804523,15.));
+#2468=CARTESIAN_POINT('',(65.237771977202,-117.96087804523,15.));
+#2469=CARTESIAN_POINT('Origin',(55.237771977202,-117.96087804523,15.));
+#2470=CARTESIAN_POINT('Origin',(63.237771977202,-117.96087804523,15.));
+#2471=CARTESIAN_POINT('Origin',(63.237771977202,-111.858747300533,15.));
+#2472=CARTESIAN_POINT('',(65.237771977202,-79.256616555836,15.));
+#2473=CARTESIAN_POINT('Origin',(63.237771977202,-79.256616555836,15.));
+#2474=CARTESIAN_POINT('',(65.237771977202,-111.858747300533,15.));
+#2475=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,15.));
+#2476=CARTESIAN_POINT('',(51.9945287339588,-69.7971570963765,15.));
+#2477=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,15.));
+#2478=CARTESIAN_POINT('Origin',(52.6431773826074,-71.6890489882684,15.));
+#2479=CARTESIAN_POINT('Origin',(-4.76222802279802,95.7433834441657,15.));
+#2480=CARTESIAN_POINT('',(-61.5189847795548,-69.7971570963765,15.));
+#2481=CARTESIAN_POINT('Origin',(-62.1676334282034,-71.6890489882684,15.));
+#2482=CARTESIAN_POINT('Origin',(-4.76222802279802,95.7433834441657,15.));
+#2483=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,15.));
+#2484=CARTESIAN_POINT('',(-74.762228022798,-79.256616555836,15.));
+#2485=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,15.));
+#2486=CARTESIAN_POINT('Origin',(-72.762228022798,-79.256616555836,15.));
+#2487=CARTESIAN_POINT('Origin',(-72.762228022798,-92.5066165558359,15.));
+#2488=CARTESIAN_POINT('',(-74.762228022798,-117.96087804523,15.));
+#2489=CARTESIAN_POINT('Origin',(-72.762228022798,-117.96087804523,15.));
+#2490=CARTESIAN_POINT('',(-74.762228022798,-92.5066165558359,15.));
+#2491=CARTESIAN_POINT('Origin',(-64.762228022798,-117.96087804523,15.));
+#2492=CARTESIAN_POINT('',(-68.3985916591616,-127.276287832466,15.));
+#2493=CARTESIAN_POINT('Origin',(-64.762228022798,-117.96087804523,15.));
+#2494=CARTESIAN_POINT('Origin',(-67.6713189318889,-125.413205875019,15.));
+#2495=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,15.));
+#2496=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,15.));
+#2497=CARTESIAN_POINT('Origin',(20.237771977202,-124.006616555836,15.));
+#2498=CARTESIAN_POINT('',(22.237771977202,-124.006616555836,15.));
+#2499=CARTESIAN_POINT('Origin',(-18.262228022798,-140.256616555836,15.));
+#2500=CARTESIAN_POINT('',(-18.262228022798,-142.256616555836,15.));
+#2501=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,0.));
+#2502=CARTESIAN_POINT('',(-68.3985916591616,-127.276287832466,0.));
+#2503=CARTESIAN_POINT('',(-68.3985916591616,-127.276287832466,0.));
+#2504=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,0.));
+#2505=CARTESIAN_POINT('Origin',(-64.762228022798,-117.96087804523,0.));
+#2506=CARTESIAN_POINT('',(-74.762228022798,-117.96087804523,0.));
+#2507=CARTESIAN_POINT('',(-74.762228022798,-117.96087804523,0.));
+#2508=CARTESIAN_POINT('',(-73.3627070104871,-123.063011048428,0.));
+#2509=CARTESIAN_POINT('Origin',(-64.762228022798,-117.96087804523,0.));
+#2510=CARTESIAN_POINT('',(-73.3627070104871,-123.063011048428,14.));
+#2511=CARTESIAN_POINT('',(-73.3627070104871,-123.063011048428,14.));
+#2512=CARTESIAN_POINT('',(-73.0194562612456,-123.601638793408,14.));
+#2513=CARTESIAN_POINT('Origin',(-64.762228022798,-117.96087804523,14.));
+#2514=CARTESIAN_POINT('',(-73.0194562612456,-123.601638793408,0.));
+#2515=CARTESIAN_POINT('',(-73.0194562612456,-123.601638793408,14.));
+#2516=CARTESIAN_POINT('Origin',(-64.762228022798,-117.96087804523,0.));
+#2517=CARTESIAN_POINT('Origin',(-74.762228022798,-79.256616555836,0.));
+#2518=CARTESIAN_POINT('',(-74.762228022798,-79.256616555836,0.));
+#2519=CARTESIAN_POINT('',(-74.762228022798,-79.256616555836,0.));
+#2520=CARTESIAN_POINT('',(-74.762228022798,-79.256616555836,0.));
+#2521=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,0.));
+#2522=CARTESIAN_POINT('',(-61.5189847795548,-69.7971570963765,0.));
+#2523=CARTESIAN_POINT('',(-61.5189847795548,-69.7971570963765,0.));
+#2524=CARTESIAN_POINT('',(-70.574609959988,-71.1192818437679,0.));
+#2525=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,0.));
+#2526=CARTESIAN_POINT('',(-70.574609959988,-71.1192818437679,14.));
+#2527=CARTESIAN_POINT('',(-70.574609959988,-71.1192818437679,14.));
+#2528=CARTESIAN_POINT('',(-70.9278290751458,-71.3835381449926,14.));
+#2529=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,14.));
+#2530=CARTESIAN_POINT('',(-70.9278290751458,-71.3835381449926,0.));
+#2531=CARTESIAN_POINT('',(-70.9278290751458,-71.3835381449926,14.));
+#2532=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,0.));
+#2533=CARTESIAN_POINT('Origin',(-4.76222802279802,95.7433834441657,0.));
+#2534=CARTESIAN_POINT('',(51.9945287339588,-69.7971570963765,0.));
+#2535=CARTESIAN_POINT('',(51.9945287339588,-69.7971570963765,0.));
+#2536=CARTESIAN_POINT('Origin',(-4.76222802279802,95.7433834441657,0.));
+#2537=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,0.));
+#2538=CARTESIAN_POINT('',(65.237771977202,-79.256616555836,0.));
+#2539=CARTESIAN_POINT('',(65.237771977202,-79.256616555836,0.));
+#2540=CARTESIAN_POINT('',(61.4033730295497,-71.3835381449926,0.));
+#2541=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,0.));
+#2542=CARTESIAN_POINT('',(61.4033730295497,-71.3835381449926,14.));
+#2543=CARTESIAN_POINT('',(61.4033730295497,-71.3835381449926,14.));
+#2544=CARTESIAN_POINT('',(61.050153914392,-71.1192818437679,14.));
+#2545=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,14.));
+#2546=CARTESIAN_POINT('',(61.050153914392,-71.1192818437679,0.));
+#2547=CARTESIAN_POINT('',(61.050153914392,-71.1192818437679,14.));
+#2548=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,0.));
+#2549=CARTESIAN_POINT('Origin',(65.237771977202,-117.96087804523,0.));
+#2550=CARTESIAN_POINT('',(65.237771977202,-117.96087804523,0.));
+#2551=CARTESIAN_POINT('',(65.237771977202,-117.96087804523,0.));
+#2552=CARTESIAN_POINT('',(65.237771977202,-117.96087804523,0.));
+#2553=CARTESIAN_POINT('Origin',(55.237771977202,-117.96087804523,0.));
+#2554=CARTESIAN_POINT('',(58.8741356135656,-127.276287832466,0.));
+#2555=CARTESIAN_POINT('',(58.8741356135656,-127.276287832466,0.));
+#2556=CARTESIAN_POINT('',(63.4950002156496,-123.601638793408,0.));
+#2557=CARTESIAN_POINT('Origin',(55.237771977202,-117.96087804523,0.));
+#2558=CARTESIAN_POINT('',(63.4950002156496,-123.601638793408,14.));
+#2559=CARTESIAN_POINT('',(63.4950002156496,-123.601638793408,14.));
+#2560=CARTESIAN_POINT('',(63.838250964891,-123.063011048428,14.));
+#2561=CARTESIAN_POINT('Origin',(55.237771977202,-117.96087804523,14.));
+#2562=CARTESIAN_POINT('',(63.838250964891,-123.063011048428,0.));
+#2563=CARTESIAN_POINT('',(63.838250964891,-123.063011048428,14.));
+#2564=CARTESIAN_POINT('Origin',(55.237771977202,-117.96087804523,0.));
+#2565=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,0.));
+#2566=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,0.));
+#2567=CARTESIAN_POINT('Origin',(7.73777197720199,-142.256616555836,-1.49999999999999));
+#2568=CARTESIAN_POINT('',(16.1043722425427,-142.256616555836,0.));
+#2569=CARTESIAN_POINT('',(16.1043722425427,-139.256616555836,0.));
+#2570=CARTESIAN_POINT('',(16.1043722425427,-142.256616555836,0.));
+#2571=CARTESIAN_POINT('',(-0.628828288138764,-142.256616555836,0.));
+#2572=CARTESIAN_POINT('Origin',(7.73777197720199,-142.256616555836,-1.49999999999999));
+#2573=CARTESIAN_POINT('',(-0.628828288138764,-139.256616555836,0.));
+#2574=CARTESIAN_POINT('',(-0.628828288138764,-142.256616555836,0.));
+#2575=CARTESIAN_POINT('Origin',(7.73777197720199,-139.256616555836,-1.49999999999999));
+#2576=CARTESIAN_POINT('Origin',(-17.262228022798,-142.256616555836,-1.5));
+#2577=CARTESIAN_POINT('',(-8.89562775745725,-142.256616555836,0.));
+#2578=CARTESIAN_POINT('',(-8.89562775745725,-139.256616555836,0.));
+#2579=CARTESIAN_POINT('',(-8.89562775745725,-142.256616555836,0.));
+#2580=CARTESIAN_POINT('',(-25.6288282881388,-142.256616555836,0.));
+#2581=CARTESIAN_POINT('Origin',(-17.262228022798,-142.256616555836,-1.5));
+#2582=CARTESIAN_POINT('',(-25.6288282881388,-139.256616555836,0.));
+#2583=CARTESIAN_POINT('',(-25.6288282881388,-142.256616555836,0.));
+#2584=CARTESIAN_POINT('Origin',(-17.262228022798,-139.256616555836,-1.5));
+#2585=CARTESIAN_POINT('Origin',(-4.76222802279802,-105.756616555836,0.));
+#2586=CARTESIAN_POINT('',(-31.762228022798,-142.256616555836,0.));
+#2587=CARTESIAN_POINT('',(-18.262228022798,-139.256616555836,0.));
+#2588=CARTESIAN_POINT('Origin',(-4.76222802279802,-105.756616555836,0.));
+#2589=CARTESIAN_POINT('',(-31.762228022798,-137.161214528244,0.));
+#2590=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,0.));
+#2591=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,0.));
+#2592=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,0.));
+#2593=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,0.));
+#2594=CARTESIAN_POINT('',(22.237771977202,-142.256616555836,0.));
+#2595=CARTESIAN_POINT('',(-31.762228022798,-142.256616555836,0.));
+#2596=CARTESIAN_POINT('',(19.237771977202,-139.256616555836,0.));
+#2597=CARTESIAN_POINT('',(-18.262228022798,-139.256616555836,0.));
+#2598=CARTESIAN_POINT('',(19.237771977202,-134.573967404186,0.));
+#2599=CARTESIAN_POINT('',(19.237771977202,-124.006616555836,0.));
+#2600=CARTESIAN_POINT('',(56.7770675495705,-124.870797438025,0.));
+#2601=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,0.));
+#2602=CARTESIAN_POINT('',(62.237771977202,-116.494213758335,0.));
+#2603=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,0.));
+#2604=CARTESIAN_POINT('',(62.237771977202,-79.256616555836,0.));
+#2605=CARTESIAN_POINT('',(62.237771977202,-111.858747300533,0.));
+#2606=CARTESIAN_POINT('',(62.17585919136,-78.3276677904362,0.));
+#2607=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,0.));
+#2608=CARTESIAN_POINT('',(54.1703836157224,-72.3384750361952,0.));
+#2609=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,0.));
+#2610=CARTESIAN_POINT('',(52.9675017069317,-72.6349949342144,0.));
+#2611=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,0.));
+#2612=CARTESIAN_POINT('',(-62.4919577525278,-72.6349949342144,0.));
+#2613=CARTESIAN_POINT('Origin',(-4.76222802279802,95.7433834441657,0.));
+#2614=CARTESIAN_POINT('',(-63.6948396613184,-72.3384750361952,0.));
+#2615=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,0.));
+#2616=CARTESIAN_POINT('',(-71.700315236956,-78.3276677904362,0.));
+#2617=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,0.));
+#2618=CARTESIAN_POINT('',(-71.762228022798,-79.256616555836,0.));
+#2619=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,0.));
+#2620=CARTESIAN_POINT('',(-71.762228022798,-116.494213758335,0.));
+#2621=CARTESIAN_POINT('',(-71.762228022798,-92.5066165558359,0.));
+#2622=CARTESIAN_POINT('',(-66.3015235951666,-124.870797438025,0.));
+#2623=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,0.));
+#2624=CARTESIAN_POINT('',(-28.762228022798,-134.573967404186,0.));
+#2625=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,0.));
+#2626=CARTESIAN_POINT('',(-28.762228022798,-139.256616555836,0.));
+#2627=CARTESIAN_POINT('',(-28.762228022798,-121.45891554204,0.));
+#2628=CARTESIAN_POINT('',(-18.262228022798,-139.256616555836,0.));
+#2629=CARTESIAN_POINT('',(-31.762228022798,-142.256616555836,0.));
+#2630=CARTESIAN_POINT('',(-65.258910811072,-75.2510899592052,0.));
+#2631=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,0.));
+#2632=CARTESIAN_POINT('',(60.7344547654759,-75.2510899592052,0.));
+#2633=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,0.));
+#2634=CARTESIAN_POINT('',(-66.4831134995567,-120.650717393207,0.));
+#2635=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,0.));
+#2636=CARTESIAN_POINT('',(61.9586574539607,-120.650717393207,0.));
+#2637=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,0.));
+#2638=CARTESIAN_POINT('Origin',(-31.762228022798,-139.256616555836,0.));
+#2639=CARTESIAN_POINT('',(-28.762228022798,-139.256616555836,14.));
+#2640=CARTESIAN_POINT('',(-28.762228022798,-139.256616555836,0.));
+#2641=CARTESIAN_POINT('',(19.237771977202,-139.256616555836,14.));
+#2642=CARTESIAN_POINT('',(-18.262228022798,-139.256616555836,14.));
+#2643=CARTESIAN_POINT('',(19.237771977202,-139.256616555836,0.));
+#2644=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,0.));
+#2645=CARTESIAN_POINT('',(61.9586574539607,-120.650717393207,0.));
+#2646=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,0.));
+#2647=CARTESIAN_POINT('',(-66.4831134995567,-120.650717393207,0.));
+#2648=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,0.));
+#2649=CARTESIAN_POINT('',(60.7344547654759,-75.2510899592052,0.));
+#2650=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,0.));
+#2651=CARTESIAN_POINT('',(-65.258910811072,-75.2510899592052,0.));
+#2652=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,14.));
+#2653=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,14.));
+#2654=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,14.));
+#2655=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,14.));
+#2656=CARTESIAN_POINT('',(62.237771977202,-116.494213758335,14.));
+#2657=CARTESIAN_POINT('',(62.237771977202,-116.494213758335,14.));
+#2658=CARTESIAN_POINT('',(56.7770675495705,-124.870797438025,14.));
+#2659=CARTESIAN_POINT('',(56.7770675495705,-124.870797438025,14.));
+#2660=CARTESIAN_POINT('Origin',(59.4586574539607,-120.650717393207,14.));
+#2661=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,14.));
+#2662=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,14.));
+#2663=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,14.));
+#2664=CARTESIAN_POINT('',(-66.3015235951666,-124.870797438025,14.));
+#2665=CARTESIAN_POINT('',(-66.3015235951666,-124.870797438025,14.));
+#2666=CARTESIAN_POINT('',(-71.762228022798,-116.494213758335,14.));
+#2667=CARTESIAN_POINT('',(-71.762228022798,-116.494213758335,14.));
+#2668=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,14.));
+#2669=CARTESIAN_POINT('Origin',(-68.9831134995567,-120.650717393207,14.));
+#2670=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,14.));
+#2671=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,14.));
+#2672=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,14.));
+#2673=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,14.));
+#2674=CARTESIAN_POINT('',(62.17585919136,-78.3276677904362,14.));
+#2675=CARTESIAN_POINT('',(62.17585919136,-78.3276677904362,14.));
+#2676=CARTESIAN_POINT('',(54.1703836157224,-72.3384750361952,14.));
+#2677=CARTESIAN_POINT('Origin',(58.2344547654759,-75.2510899592052,14.));
+#2678=CARTESIAN_POINT('',(54.1703836157224,-72.3384750361952,14.));
+#2679=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,14.));
+#2680=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,14.));
+#2681=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,14.));
+#2682=CARTESIAN_POINT('',(-71.700315236956,-78.3276677904362,14.));
+#2683=CARTESIAN_POINT('',(-71.700315236956,-78.3276677904362,14.));
+#2684=CARTESIAN_POINT('',(-63.6948396613184,-72.3384750361952,14.));
+#2685=CARTESIAN_POINT('',(-63.6948396613184,-72.3384750361952,14.));
+#2686=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,14.));
+#2687=CARTESIAN_POINT('Origin',(-67.758910811072,-75.2510899592052,14.));
+#2688=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,0.));
+#2689=CARTESIAN_POINT('',(19.237771977202,-134.573967404186,14.));
+#2690=CARTESIAN_POINT('',(19.237771977202,-134.573967404186,0.));
+#2691=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,14.));
+#2692=CARTESIAN_POINT('Origin',(-71.762228022798,-79.256616555836,0.));
+#2693=CARTESIAN_POINT('',(-71.762228022798,-79.256616555836,14.));
+#2694=CARTESIAN_POINT('',(-71.762228022798,-79.256616555836,0.));
+#2695=CARTESIAN_POINT('',(-71.762228022798,-92.5066165558359,14.));
+#2696=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,0.));
+#2697=CARTESIAN_POINT('',(52.9675017069317,-72.6349949342144,14.));
+#2698=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,14.));
+#2699=CARTESIAN_POINT('',(52.9675017069317,-72.6349949342144,0.));
+#2700=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,0.));
+#2701=CARTESIAN_POINT('',(62.237771977202,-79.256616555836,14.));
+#2702=CARTESIAN_POINT('',(62.237771977202,-79.256616555836,0.));
+#2703=CARTESIAN_POINT('Origin',(55.237771977202,-79.256616555836,14.));
+#2704=CARTESIAN_POINT('Origin',(-4.76222802279802,-105.756616555836,14.));
+#2705=CARTESIAN_POINT('',(19.237771977202,-124.006616555836,14.));
+#2706=CARTESIAN_POINT('',(-28.762228022798,-134.573967404186,14.));
+#2707=CARTESIAN_POINT('',(-28.762228022798,-121.45891554204,14.));
+#2708=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,14.));
+#2709=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,14.));
+#2710=CARTESIAN_POINT('',(-62.4919577525278,-72.6349949342144,14.));
+#2711=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,14.));
+#2712=CARTESIAN_POINT('Origin',(-4.76222802279802,95.7433834441657,14.));
+#2713=CARTESIAN_POINT('',(62.237771977202,-111.858747300533,14.));
+#2714=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,0.));
+#2715=CARTESIAN_POINT('',(-62.4919577525278,-72.6349949342144,0.));
+#2716=CARTESIAN_POINT('Origin',(-64.762228022798,-79.256616555836,0.));
+#2717=CARTESIAN_POINT('Origin',(-4.76222802279802,95.7433834441657,0.));
+#2718=CARTESIAN_POINT('Origin',(62.237771977202,-117.96087804523,0.));
+#2719=CARTESIAN_POINT('Origin',(19.237771977202,-142.256616555836,0.));
+#2720=CARTESIAN_POINT('Origin',(-28.762228022798,-137.161214528244,0.));
+#2721=CARTESIAN_POINT('',(-28.762228022798,-134.573967404186,0.));
+#2722=CARTESIAN_POINT('Origin',(-4.76222802279802,35.7433834441644,0.));
+#2723=CARTESIAN_POINT('Origin',(22.237771977202,-142.256616555836,0.));
+#2724=CARTESIAN_POINT('Origin',(-31.762228022798,-142.256616555836,0.));
+#2725=CARTESIAN_POINT('Origin',(-31.762228022798,-137.161214528244,0.));
+#2726=CARTESIAN_POINT('',(0.,0.,14.));
+#2727=CARTESIAN_POINT('',(0.,0.,14.));
+#2728=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#2732,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#2729=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#2732,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#2730=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#2728))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#2732,#2734,#2735))
+REPRESENTATION_CONTEXT('','3D')
+);
+#2731=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#2729))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#2732,#2734,#2735))
+REPRESENTATION_CONTEXT('','3D')
+);
+#2732=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.MILLI.,.METRE.)
+);
+#2733=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.CENTI.,.METRE.)
+);
+#2734=(
+NAMED_UNIT(*)
+PLANE_ANGLE_UNIT()
+SI_UNIT($,.RADIAN.)
+);
+#2735=(
+NAMED_UNIT(*)
+SI_UNIT($,.STERADIAN.)
+SOLID_ANGLE_UNIT()
+);
+#2736=SHAPE_DEFINITION_REPRESENTATION(#2737,#2738);
+#2737=PRODUCT_DEFINITION_SHAPE('',$,#2740);
+#2738=SHAPE_REPRESENTATION('',(#1516),#2730);
+#2739=PRODUCT_DEFINITION_CONTEXT('part definition',#2744,'design');
+#2740=PRODUCT_DEFINITION('deckel','deckel',#2741,#2739);
+#2741=PRODUCT_DEFINITION_FORMATION('',$,#2746);
+#2742=PRODUCT_RELATED_PRODUCT_CATEGORY('deckel','deckel',(#2746));
+#2743=APPLICATION_PROTOCOL_DEFINITION('international standard',
+'automotive_design',2009,#2744);
+#2744=APPLICATION_CONTEXT(
+'Core Data for Automotive Mechanical Design Process');
+#2745=PRODUCT_CONTEXT('part definition',#2744,'mechanical');
+#2746=PRODUCT('deckel','deckel',$,(#2745));
+#2747=PRESENTATION_STYLE_ASSIGNMENT((#2749));
+#2748=PRESENTATION_STYLE_ASSIGNMENT((#2750));
+#2749=SURFACE_STYLE_USAGE(.BOTH.,#2753);
+#2750=SURFACE_STYLE_USAGE(.BOTH.,#2754);
+#2751=SURFACE_STYLE_RENDERING_WITH_PROPERTIES($,#2761,(#2752));
+#2752=SURFACE_STYLE_TRANSPARENT(0.);
+#2753=SURFACE_SIDE_STYLE('',(#2755,#2751));
+#2754=SURFACE_SIDE_STYLE('',(#2756));
+#2755=SURFACE_STYLE_FILL_AREA(#2757);
+#2756=SURFACE_STYLE_FILL_AREA(#2758);
+#2757=FILL_AREA_STYLE('',(#2759));
+#2758=FILL_AREA_STYLE('',(#2760));
+#2759=FILL_AREA_STYLE_COLOUR('',#2761);
+#2760=FILL_AREA_STYLE_COLOUR('',#2762);
+#2761=COLOUR_RGB('',0.749019607843137,0.749019607843137,0.749019607843137);
+#2762=COLOUR_RGB('',1.,1.,0.);
+ENDSEC;
+END-ISO-10303-21;
diff --git a/Komponenten/spacer.ipt b/Komponenten/spacer.ipt
new file mode 100644
index 0000000000000000000000000000000000000000..6fbb296799e776df24684f1d1618e7b954004ce0
Binary files /dev/null and b/Komponenten/spacer.ipt differ
diff --git a/Komponenten/spacer.stp b/Komponenten/spacer.stp
new file mode 100644
index 0000000000000000000000000000000000000000..d53d48cd256d71af9b25dad7e1576d8cf0f9ceb4
--- /dev/null
+++ b/Komponenten/spacer.stp
@@ -0,0 +1,217 @@
+ISO-10303-21;
+HEADER;
+/* Generated by software containing ST-Developer
+ * from STEP Tools, Inc. (www.steptools.com) 
+ */
+
+FILE_DESCRIPTION(
+/* description */ (''),
+/* implementation_level */ '2;1');
+
+FILE_NAME(
+/* name */ 'spacer.stp',
+/* time_stamp */ '2025-01-13T19:50:38+01:00',
+/* author */ ('seb'),
+/* organization */ (''),
+/* preprocessor_version */ 'ST-DEVELOPER v20',
+/* originating_system */ 'Autodesk Inventor 2025',
+/* authorisation */ '');
+
+FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }'));
+ENDSEC;
+
+DATA;
+#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#134);
+#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#141,#12);
+#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#133);
+#13=STYLED_ITEM('',(#150),#14);
+#14=MANIFOLD_SOLID_BREP('Volumenk\X\F6rper1',#65);
+#15=FACE_BOUND('',#26,.T.);
+#16=FACE_BOUND('',#28,.T.);
+#17=PLANE('',#94);
+#18=PLANE('',#95);
+#19=FACE_OUTER_BOUND('',#23,.T.);
+#20=FACE_OUTER_BOUND('',#24,.T.);
+#21=FACE_OUTER_BOUND('',#25,.T.);
+#22=FACE_OUTER_BOUND('',#27,.T.);
+#23=EDGE_LOOP('',(#47,#48,#49,#50));
+#24=EDGE_LOOP('',(#51,#52,#53,#54));
+#25=EDGE_LOOP('',(#55));
+#26=EDGE_LOOP('',(#56));
+#27=EDGE_LOOP('',(#57));
+#28=EDGE_LOOP('',(#58));
+#29=LINE('',#121,#31);
+#30=LINE('',#127,#32);
+#31=VECTOR('',#102,2.25);
+#32=VECTOR('',#109,3.75);
+#33=CIRCLE('',#89,2.25);
+#34=CIRCLE('',#90,2.25);
+#35=CIRCLE('',#92,3.75);
+#36=CIRCLE('',#93,3.75);
+#37=VERTEX_POINT('',#118);
+#38=VERTEX_POINT('',#120);
+#39=VERTEX_POINT('',#124);
+#40=VERTEX_POINT('',#126);
+#41=EDGE_CURVE('',#37,#37,#33,.T.);
+#42=EDGE_CURVE('',#37,#38,#29,.T.);
+#43=EDGE_CURVE('',#38,#38,#34,.T.);
+#44=EDGE_CURVE('',#39,#39,#35,.T.);
+#45=EDGE_CURVE('',#39,#40,#30,.T.);
+#46=EDGE_CURVE('',#40,#40,#36,.T.);
+#47=ORIENTED_EDGE('',*,*,#41,.F.);
+#48=ORIENTED_EDGE('',*,*,#42,.T.);
+#49=ORIENTED_EDGE('',*,*,#43,.T.);
+#50=ORIENTED_EDGE('',*,*,#42,.F.);
+#51=ORIENTED_EDGE('',*,*,#44,.F.);
+#52=ORIENTED_EDGE('',*,*,#45,.T.);
+#53=ORIENTED_EDGE('',*,*,#46,.T.);
+#54=ORIENTED_EDGE('',*,*,#45,.F.);
+#55=ORIENTED_EDGE('',*,*,#44,.T.);
+#56=ORIENTED_EDGE('',*,*,#41,.T.);
+#57=ORIENTED_EDGE('',*,*,#46,.F.);
+#58=ORIENTED_EDGE('',*,*,#43,.F.);
+#59=CYLINDRICAL_SURFACE('',#88,2.25);
+#60=CYLINDRICAL_SURFACE('',#91,3.75);
+#61=ADVANCED_FACE('',(#19),#59,.F.);
+#62=ADVANCED_FACE('',(#20),#60,.T.);
+#63=ADVANCED_FACE('',(#21,#15),#17,.T.);
+#64=ADVANCED_FACE('',(#22,#16),#18,.F.);
+#65=CLOSED_SHELL('',(#61,#62,#63,#64));
+#66=DERIVED_UNIT_ELEMENT(#69,1.);
+#67=DERIVED_UNIT_ELEMENT(#136,-3.);
+#68=DIMENSIONAL_EXPONENTS(0.,1.,0.,0.,0.,0.,0.);
+#69=(
+CONVERSION_BASED_UNIT('gram',#71)
+MASS_UNIT()
+NAMED_UNIT(#68)
+);
+#70=(
+MASS_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.KILO.,.GRAM.)
+);
+#71=MASS_MEASURE_WITH_UNIT(MASS_MEASURE(0.001),#70);
+#72=DERIVED_UNIT((#66,#67));
+#73=MEASURE_REPRESENTATION_ITEM('density measure',
+POSITIVE_RATIO_MEASURE(1.),#72);
+#74=PROPERTY_DEFINITION_REPRESENTATION(#79,#76);
+#75=PROPERTY_DEFINITION_REPRESENTATION(#80,#77);
+#76=REPRESENTATION('material name',(#78),#133);
+#77=REPRESENTATION('density',(#73),#133);
+#78=DESCRIPTIVE_REPRESENTATION_ITEM('Generisch','Generisch');
+#79=PROPERTY_DEFINITION('material property','material name',#143);
+#80=PROPERTY_DEFINITION('material property','density of part',#143);
+#81=DATE_TIME_ROLE('creation_date');
+#82=APPLIED_DATE_AND_TIME_ASSIGNMENT(#83,#81,(#143));
+#83=DATE_AND_TIME(#84,#85);
+#84=CALENDAR_DATE(2025,7,1);
+#85=LOCAL_TIME(0,0,0.,#86);
+#86=COORDINATED_UNIVERSAL_TIME_OFFSET(0,0,.BEHIND.);
+#87=AXIS2_PLACEMENT_3D('',#116,#96,#97);
+#88=AXIS2_PLACEMENT_3D('',#117,#98,#99);
+#89=AXIS2_PLACEMENT_3D('',#119,#100,#101);
+#90=AXIS2_PLACEMENT_3D('',#122,#103,#104);
+#91=AXIS2_PLACEMENT_3D('',#123,#105,#106);
+#92=AXIS2_PLACEMENT_3D('',#125,#107,#108);
+#93=AXIS2_PLACEMENT_3D('',#128,#110,#111);
+#94=AXIS2_PLACEMENT_3D('',#129,#112,#113);
+#95=AXIS2_PLACEMENT_3D('',#130,#114,#115);
+#96=DIRECTION('axis',(0.,0.,1.));
+#97=DIRECTION('refdir',(1.,0.,0.));
+#98=DIRECTION('center_axis',(0.,0.,1.));
+#99=DIRECTION('ref_axis',(-1.,0.,0.));
+#100=DIRECTION('center_axis',(0.,0.,-1.));
+#101=DIRECTION('ref_axis',(-1.,0.,0.));
+#102=DIRECTION('',(0.,0.,-1.));
+#103=DIRECTION('center_axis',(0.,0.,-1.));
+#104=DIRECTION('ref_axis',(-1.,0.,0.));
+#105=DIRECTION('center_axis',(0.,0.,1.));
+#106=DIRECTION('ref_axis',(1.,0.,0.));
+#107=DIRECTION('center_axis',(0.,0.,1.));
+#108=DIRECTION('ref_axis',(1.,0.,0.));
+#109=DIRECTION('',(0.,0.,-1.));
+#110=DIRECTION('center_axis',(0.,0.,1.));
+#111=DIRECTION('ref_axis',(1.,0.,0.));
+#112=DIRECTION('center_axis',(0.,0.,1.));
+#113=DIRECTION('ref_axis',(1.,0.,0.));
+#114=DIRECTION('center_axis',(0.,0.,1.));
+#115=DIRECTION('ref_axis',(1.,0.,0.));
+#116=CARTESIAN_POINT('',(0.,0.,0.));
+#117=CARTESIAN_POINT('Origin',(0.,0.,0.));
+#118=CARTESIAN_POINT('',(2.25,2.75545529808154E-16,10.));
+#119=CARTESIAN_POINT('Origin',(0.,0.,10.));
+#120=CARTESIAN_POINT('',(2.25,2.75545529808154E-16,0.));
+#121=CARTESIAN_POINT('',(2.25,2.75545529808154E-16,0.));
+#122=CARTESIAN_POINT('Origin',(0.,0.,0.));
+#123=CARTESIAN_POINT('Origin',(0.,0.,0.));
+#124=CARTESIAN_POINT('',(-3.75,-4.59242549680257E-16,10.));
+#125=CARTESIAN_POINT('Origin',(0.,0.,10.));
+#126=CARTESIAN_POINT('',(-3.75,-4.59242549680257E-16,0.));
+#127=CARTESIAN_POINT('',(-3.75,-4.59242549680257E-16,0.));
+#128=CARTESIAN_POINT('Origin',(0.,0.,0.));
+#129=CARTESIAN_POINT('Origin',(0.,0.,10.));
+#130=CARTESIAN_POINT('Origin',(0.,0.,0.));
+#131=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#135,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#132=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#135,
+'DISTANCE_ACCURACY_VALUE',
+'Maximum model space distance between geometric entities at asserted c
+onnectivities');
+#133=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#131))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#135,#137,#138))
+REPRESENTATION_CONTEXT('','3D')
+);
+#134=(
+GEOMETRIC_REPRESENTATION_CONTEXT(3)
+GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#132))
+GLOBAL_UNIT_ASSIGNED_CONTEXT((#135,#137,#138))
+REPRESENTATION_CONTEXT('','3D')
+);
+#135=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.MILLI.,.METRE.)
+);
+#136=(
+LENGTH_UNIT()
+NAMED_UNIT(*)
+SI_UNIT(.CENTI.,.METRE.)
+);
+#137=(
+NAMED_UNIT(*)
+PLANE_ANGLE_UNIT()
+SI_UNIT($,.RADIAN.)
+);
+#138=(
+NAMED_UNIT(*)
+SI_UNIT($,.STERADIAN.)
+SOLID_ANGLE_UNIT()
+);
+#139=SHAPE_DEFINITION_REPRESENTATION(#140,#141);
+#140=PRODUCT_DEFINITION_SHAPE('',$,#143);
+#141=SHAPE_REPRESENTATION('',(#87),#133);
+#142=PRODUCT_DEFINITION_CONTEXT('part definition',#147,'design');
+#143=PRODUCT_DEFINITION('spacer','spacer',#144,#142);
+#144=PRODUCT_DEFINITION_FORMATION('',$,#149);
+#145=PRODUCT_RELATED_PRODUCT_CATEGORY('spacer','spacer',(#149));
+#146=APPLICATION_PROTOCOL_DEFINITION('international standard',
+'automotive_design',2009,#147);
+#147=APPLICATION_CONTEXT(
+'Core Data for Automotive Mechanical Design Process');
+#148=PRODUCT_CONTEXT('part definition',#147,'mechanical');
+#149=PRODUCT('spacer','spacer',$,(#148));
+#150=PRESENTATION_STYLE_ASSIGNMENT((#151));
+#151=SURFACE_STYLE_USAGE(.BOTH.,#154);
+#152=SURFACE_STYLE_RENDERING_WITH_PROPERTIES($,#158,(#153));
+#153=SURFACE_STYLE_TRANSPARENT(0.);
+#154=SURFACE_SIDE_STYLE('',(#155,#152));
+#155=SURFACE_STYLE_FILL_AREA(#156);
+#156=FILL_AREA_STYLE('',(#157));
+#157=FILL_AREA_STYLE_COLOUR('',#158);
+#158=COLOUR_RGB('',0.749019607843137,0.749019607843137,0.749019607843137);
+ENDSEC;
+END-ISO-10303-21;
diff --git a/README.md b/README.md
index 1dfc050b3fc4db68e296d16de1c92f9d1b2babbd..5ac2f18780d8fddf433e9fe376ab5f55c29a412b 100644
--- a/README.md
+++ b/README.md
@@ -1,93 +1,32 @@
-# turtlebot4
+<img src="/Bilder/igmr.png" alt="IGMR" width="500">
 
+# Navigation mit dem Turtlebot 4
+*Eine Projektarbeit von Julian Kühne und Sebastian Matz betreut von Sophie Charlotte Keunecke am IGMR der RWTH*
 
+<img src="/Bilder/seitlich.jpg" alt="Turtlebot" width="800">
 
-## Getting started
+### Ziel der Projektarbeit
+Inbetriebnahme eines Turtlebot4 mit ROS2 Humble auf einem Ubuntu 22.04, Implementierung externer Sensoren und Ausführen eines Navigationsszenarios. Dieses Repository soll der Dokumentation unserer Arbeit dienen und sie für andere zugänglich machen.
 
-To make it easy for you to get started with GitLab, here's a list of recommended next steps.
+### Struktur der Dokumentation
+1. [Inbetriebnahme Turtlebot 4](Dokumentation/Inbetriebnahme_Turtlebot_4.md)
+2. [ROS Basics](Dokumentation/ROS2_Basics.md)
+3. [Sensoren](Dokumentation/Sensoren.md)
+4. [Navigation](Dokumentation/Navigation.md)
 
-Already a pro? Just edit this README.md and make it your own. Want to make it easy? [Use the template at the bottom](#editing-this-readme)!
+### Der Turtlebot 4
 
-## Add your files
 
-- [ ] [Create](https://docs.gitlab.com/ee/user/project/repository/web_editor.html#create-a-file) or [upload](https://docs.gitlab.com/ee/user/project/repository/web_editor.html#upload-a-file) files
-- [ ] [Add files using the command line](https://docs.gitlab.com/ee/gitlab-basics/add-file.html#add-a-file-using-the-command-line) or push an existing Git repository with the following command:
+<img src="https://turtlebot.github.io/turtlebot4-user-manual/overview/media/standard_render.png" alt="GPIO Belegung" width="500">
 
-```
-cd existing_repo
-git remote add origin https://git-ce.rwth-aachen.de/turtlebot_igmr/turtlebot4.git
-git branch -M main
-git push -uf origin main
-```
+*Turtlebot 4*
 
-## Integrate with your tools
+Ein **TurtleBot 4** ist ein robuster und vielseitiger mobiler Roboter, der speziell für Forschung, Lehre und Entwicklung im Bereich Robotik konzipiert wurde. Es handelt sich um eine der neuesten Versionen der TurtleBot-Serie, die auf dem ROS (Robot Operating System) basiert und für die Verwendung mit **ROS 2 Humble** optimiert ist. Der TurtleBot 4 ist auf einem **Raspberry Pi 4** aufgebaut und bietet eine Plattform für Experimente und Anwendungen in der Robotik.
 
-- [ ] [Set up project integrations](https://git-ce.rwth-aachen.de/turtlebot_igmr/turtlebot4/-/settings/integrations)
+### GPT zu dieser Projektarbeit
+ChatGPT ist sehr hilfreich bei der Arbeit mit dem Turtlebot. Wir haben ein GPT-Modell mit allen zu unserer Projektarbeit relevanten Daten trainiert und stellen das hier zur Verfügung: [Navigation mit dem Turtlebot 4](https://chatgpt.com/g/g-6768182420c0819180e9cc092e1ed888-navigation-mit-dem-turtlebot-4).
 
-## Collaborate with your team
-
-- [ ] [Invite team members and collaborators](https://docs.gitlab.com/ee/user/project/members/)
-- [ ] [Create a new merge request](https://docs.gitlab.com/ee/user/project/merge_requests/creating_merge_requests.html)
-- [ ] [Automatically close issues from merge requests](https://docs.gitlab.com/ee/user/project/issues/managing_issues.html#closing-issues-automatically)
-- [ ] [Enable merge request approvals](https://docs.gitlab.com/ee/user/project/merge_requests/approvals/)
-- [ ] [Set auto-merge](https://docs.gitlab.com/ee/user/project/merge_requests/merge_when_pipeline_succeeds.html)
-
-## Test and Deploy
-
-Use the built-in continuous integration in GitLab.
-
-- [ ] [Get started with GitLab CI/CD](https://docs.gitlab.com/ee/ci/quick_start/index.html)
-- [ ] [Analyze your code for known vulnerabilities with Static Application Security Testing (SAST)](https://docs.gitlab.com/ee/user/application_security/sast/)
-- [ ] [Deploy to Kubernetes, Amazon EC2, or Amazon ECS using Auto Deploy](https://docs.gitlab.com/ee/topics/autodevops/requirements.html)
-- [ ] [Use pull-based deployments for improved Kubernetes management](https://docs.gitlab.com/ee/user/clusters/agent/)
-- [ ] [Set up protected environments](https://docs.gitlab.com/ee/ci/environments/protected_environments.html)
-
-***
-
-# Editing this README
-
-When you're ready to make this README your own, just edit this file and use the handy template below (or feel free to structure it however you want - this is just a starting point!). Thanks to [makeareadme.com](https://www.makeareadme.com/) for this template.
-
-## Suggestions for a good README
-
-Every project is different, so consider which of these sections apply to yours. The sections used in the template are suggestions for most open source projects. Also keep in mind that while a README can be too long and detailed, too long is better than too short. If you think your README is too long, consider utilizing another form of documentation rather than cutting out information.
-
-## Name
-Choose a self-explaining name for your project.
-
-## Description
-Let people know what your project can do specifically. Provide context and add a link to any reference visitors might be unfamiliar with. A list of Features or a Background subsection can also be added here. If there are alternatives to your project, this is a good place to list differentiating factors.
-
-## Badges
-On some READMEs, you may see small images that convey metadata, such as whether or not all the tests are passing for the project. You can use Shields to add some to your README. Many services also have instructions for adding a badge.
-
-## Visuals
-Depending on what you are making, it can be a good idea to include screenshots or even a video (you'll frequently see GIFs rather than actual videos). Tools like ttygif can help, but check out Asciinema for a more sophisticated method.
-
-## Installation
-Within a particular ecosystem, there may be a common way of installing things, such as using Yarn, NuGet, or Homebrew. However, consider the possibility that whoever is reading your README is a novice and would like more guidance. Listing specific steps helps remove ambiguity and gets people to using your project as quickly as possible. If it only runs in a specific context like a particular programming language version or operating system or has dependencies that have to be installed manually, also add a Requirements subsection.
-
-## Usage
-Use examples liberally, and show the expected output if you can. It's helpful to have inline the smallest example of usage that you can demonstrate, while providing links to more sophisticated examples if they are too long to reasonably include in the README.
-
-## Support
-Tell people where they can go to for help. It can be any combination of an issue tracker, a chat room, an email address, etc.
-
-## Roadmap
-If you have ideas for releases in the future, it is a good idea to list them in the README.
-
-## Contributing
-State if you are open to contributions and what your requirements are for accepting them.
-
-For people who want to make changes to your project, it's helpful to have some documentation on how to get started. Perhaps there is a script that they should run or some environment variables that they need to set. Make these steps explicit. These instructions could also be useful to your future self.
-
-You can also document commands to lint the code or run tests. These steps help to ensure high code quality and reduce the likelihood that the changes inadvertently break something. Having instructions for running tests is especially helpful if it requires external setup, such as starting a Selenium server for testing in a browser.
-
-## Authors and acknowledgment
-Show your appreciation to those who have contributed to the project.
-
-## License
-For open source projects, say how it is licensed.
-
-## Project status
-If you have run out of energy or time for your project, put a note at the top of the README saying that development has slowed down or stopped completely. Someone may choose to fork your project or volunteer to step in as a maintainer or owner, allowing your project to keep going. You can also make an explicit request for maintainers.
+### Hilfreiche Links
+- [Offizielle Tutlebot 4 Dokumentation](https://turtlebot.github.io/turtlebot4-user-manual/)
+- [Offizielle Create 3 Dokumentation](https://iroboteducation.github.io/create3_docs/)
+- [Offizielle ROS2 Humble Dokumentation](https://docs.ros.org/en/humble/index.html)
\ No newline at end of file