diff --git a/.gitattributes b/.gitattributes index 1ef325f1b111266a6b26e0196871bd78baa8c2f3..1dce6c10fe08f25db67851632651db1c998c2668 100644 --- a/.gitattributes +++ b/.gitattributes @@ -57,3 +57,23 @@ saved_model/**/* filter=lfs diff=lfs merge=lfs -text # Video files - compressed *.mp4 filter=lfs diff=lfs merge=lfs -text *.webm filter=lfs diff=lfs merge=lfs -text +discord-0.0.119[[:space:]](3).deb filter=lfs diff=lfs merge=lfs -text +hardware/TRLC-DK1-Follower_v0.2.0.step filter=lfs diff=lfs merge=lfs -text +hardware/follower_STLs/dm-adapter_v0.2.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/follower_STLs/dm-idler_v0.2.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/follower_STLs/link2-3-frame_v0.2.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/follower_STLs/link3-4-frame_v0.2.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/follower_gripper_STLs/camera-shell_v0.2.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/follower_gripper_STLs/d405-holder_v0.1.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/follower_gripper_STLs/gear-rack_v0.1.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/follower_gripper_STLs/gear-shaft_v0.1.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/follower_gripper_STLs/link6-7-1_v0.2.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/follower_gripper_STLs/link6-7-2_v0.2.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/leader_STLs/gello_handle_45deg.stl filter=lfs diff=lfs merge=lfs -text +hardware/leader_STLs/gello_trigger.stl filter=lfs diff=lfs merge=lfs -text +hardware/leader_STLs/leader.3mf filter=lfs diff=lfs merge=lfs -text +hardware/leader_STLs/link0-1_v0.1.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/leader_STLs/link1-2_v0.1.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/leader_STLs/link4-5-flipped_v0.1.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/leader_STLs/link4-5_v0.1.0.stl filter=lfs diff=lfs merge=lfs -text +hardware/leader_STLs/link5-6-1_v0.1.0.stl filter=lfs diff=lfs merge=lfs -text diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..8cbfda73d8f0428dd42c73788b898e067731a067 --- /dev/null +++ b/.gitignore @@ -0,0 +1,218 @@ +.DS_Store + +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[codz] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +share/python-wheels/ +*.egg-info/ +.installed.cfg +*.egg +MANIFEST + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.nox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +*.py.cover +.hypothesis/ +.pytest_cache/ +cover/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py +db.sqlite3 +db.sqlite3-journal + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +.pybuilder/ +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# IPython +profile_default/ +ipython_config.py + +# pyenv +# For a library or package, you might want to ignore these files since the code is +# intended to run in multiple environments; otherwise, check them in: +# .python-version + +# pipenv +# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. +# However, in case of collaboration, if having platform-specific dependencies or dependencies +# having no cross-platform support, pipenv may install dependencies that don't work, or not +# install all needed dependencies. +#Pipfile.lock + +# UV +# Similar to Pipfile.lock, it is generally recommended to include uv.lock in version control. +# This is especially recommended for binary packages to ensure reproducibility, and is more +# commonly ignored for libraries. +#uv.lock + +# poetry +# Similar to Pipfile.lock, it is generally recommended to include poetry.lock in version control. +# This is especially recommended for binary packages to ensure reproducibility, and is more +# commonly ignored for libraries. +# https://python-poetry.org/docs/basic-usage/#commit-your-poetrylock-file-to-version-control +#poetry.lock +#poetry.toml + +# pdm +# Similar to Pipfile.lock, it is generally recommended to include pdm.lock in version control. +# pdm recommends including project-wide configuration in pdm.toml, but excluding .pdm-python. +# https://pdm-project.org/en/latest/usage/project/#working-with-version-control +#pdm.lock +#pdm.toml +.pdm-python +.pdm-build/ + +# pixi +# Similar to Pipfile.lock, it is generally recommended to include pixi.lock in version control. +#pixi.lock +# Pixi creates a virtual environment in the .pixi directory, just like venv module creates one +# in the .venv directory. It is recommended not to include this directory in version control. +.pixi + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow and github.com/pdm-project/pdm +__pypackages__/ + +# Celery stuff +celerybeat-schedule +celerybeat.pid + +# Redis +*.rdb +*.aof +*.pid + +# RabbitMQ +mnesia/ +rabbitmq/ +rabbitmq-data/ + +# ActiveMQ +activemq-data/ + +# SageMath parsed files +*.sage.py + +# Environments +.env +.envrc +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ +.dmypy.json +dmypy.json + +# Pyre type checker +.pyre/ + +# pytype static type analyzer +.pytype/ + +# Cython debug symbols +cython_debug/ + +# PyCharm +# JetBrains specific template is maintained in a separate JetBrains.gitignore that can +# be found at https://github.com/github/gitignore/blob/main/Global/JetBrains.gitignore +# and can be added to the global gitignore or merged into this file. For a more nuclear +# option (not recommended) you can uncomment the following to ignore the entire idea folder. +#.idea/ + +# Abstra +# Abstra is an AI-powered process automation framework. +# Ignore directories containing user credentials, local state, and settings. +# Learn more at https://abstra.io/docs +.abstra/ + +# Visual Studio Code +# Visual Studio Code specific template is maintained in a separate VisualStudioCode.gitignore +# that can be found at https://github.com/github/gitignore/blob/main/Global/VisualStudioCode.gitignore +# and can be added to the global gitignore or merged into this file. However, if you prefer, +# you could uncomment the following to ignore the entire vscode folder +# .vscode/ + +# Ruff stuff: +.ruff_cache/ + +# PyPI configuration file +.pypirc + +# Marimo +marimo/_static/ +marimo/_lsp/ +__marimo__/ + +# Streamlit +.streamlit/secrets.toml \ No newline at end of file diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000000000000000000000000000000000000..b50d3394e50c0697df7351d3a5d1bdeb34b63e6b --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "src/trlc-dk1/motors/DM_Control_Python"] + path = src/trlc-dk1/motors/DM_Control_Python + url = https://github.com/cmjang/DM_Control_Python.git diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000000000000000000000000000000000000..05f6474801b6e24df637c388e070e0ef093b43e5 --- /dev/null +++ b/LICENSE @@ -0,0 +1,273 @@ +Copyright 2025 The Robot Learning Company UG (haftungsbeschränkt). All rights reserved. + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + 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. + + + +Some of TRLC-DK1's code is derived from DM_Control_Python, which is subject to the following copyright notice: + + MIT License + + Copyright (c) 2024 cmjang + + Permission is hereby granted, free of charge, to any person obtaining a copy + of this software and associated documentation files (the "Software"), to deal + in the Software without restriction, including without limitation the rights + to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all + copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + SOFTWARE. + + + +Some of TRLC-DK1's code is derived from LeRobot, which is subject to the following copyright notice: + + Copyright 2024 The Hugging Face team. All rights reserved. + + 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. + + + +Some of TRLC-DK1's code is derived from GELLO, which is subject to the following copyright notice: + + MIT License + + Copyright (c) 2023 Philipp Wu + + Permission is hereby granted, free of charge, to any person obtaining a copy + of this software and associated documentation files (the "Software"), to deal + in the Software without restriction, including without limitation the rights + to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all + copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + SOFTWARE. \ No newline at end of file diff --git a/README.md b/README.md new file mode 100644 index 0000000000000000000000000000000000000000..adb4425b5fce7d98f6635634860b26475fe4d8b5 --- /dev/null +++ b/README.md @@ -0,0 +1,222 @@ +

+ +

+

+ + Chat on Discord + + + + + + +

+ +

An Open Source Dev Kit for AI-native Robotics

+

by The Robot Learning Company

+ +## Demo + +

+ +

+ +## CAD + + + + + + +
+ +TRLC-DK1 v0.2.0 Follower CAD (Fusion)
+ +
+
+ +TRLC-DK1 v0.2.0 Leader CAD (Fusion)
+ +
+
+Copyright 2025 The Robot Learning Company UG (haftungsbeschränkt). All rights reserved. + +## Installation + +``` +conda create -n dk1 python=3.10 +conda activate dk1 +pip install -e . +``` + +(This should also install [TRLC's fork of LeRobot](https://github.com/robot-learning-co/lerobot) and use branch `trlc-dk1`) + +## Examples + +Use [LeRobot's CLI](https://huggingface.co/docs/lerobot/il_robots) to identify your teleop and robot ports: + +``` +lerobot-find-port +``` + + +1 +0 + +lerobot-teleoperate \ + --robot.type=bi_dk1_follower \ + --robot.right_arm_port=/dev/ttyACM0 \ + --robot.left_arm_port=/dev/ttyACM1 \ + --robot.joint_velocity_scaling=1.0 \ + --robot.cameras="{ + context: {type: opencv, index_or_path: 2, width: 640, height: 360, fps: 30}, + right_wrist: {type: opencv, index_or_path: 4, width: 640, height: 360, fps: 30}, + left_wrist: {type: opencv, index_or_path: 0, width: 640, height: 360, fps: 30}, + }" \ + --teleop.type=bi_dk1_leader \ + --teleop.right_arm_port=/dev/ttyACM2 \ + --teleop.left_arm_port=/dev/ttyACM3 \ + --display_data=true \ + --display_url=100.88.6.81 + + +
+Teleoperation + +lerobot-teleoperate \ + --robot.type=bi_dk1_follower \ + --robot.right_arm_port=/dev/ttyACM3 \ + --robot.left_arm_port=/dev/ttyACM2 \ + --robot.joint_velocity_scaling=1 \ + --robot.cameras="{ + context: {type: opencv, index_or_path: 2, width: 640, height: 360, fps: 30}, + right_wrist: {type: opencv, index_or_path: 4, width: 640, height: 360, fps: 30}, + left_wrist: {type: opencv, index_or_path: 0, width: 640, height: 360, fps: 30}, + }" \ + --teleop.type=bi_dk1_leader \ + --teleop.right_arm_port=/dev/ttyACM0 \ + --teleop.left_arm_port=/dev/ttyACM1 \ + --display_data=true \ + --display_url=100.88.6.81 +```bash +lerobot-teleoperate \ + --robot.type=dk1_follower \ + --robot.port=/dev/ttyACM0 \ + --robot.joint_velocity_scaling=0.1 \ + --teleop.type=dk1_leader \ + --teleop.port=/dev/ttyACM1 \ + --display_data=true +``` + + +lerobot-teleoperate \ + --robot.type=dk1_follower \ + --robot.port=/dev/ttyACM1 \ + --robot.joint_velocity_scaling=1 \ + --teleop.type=dk1_leader \ + --teleop.port=/dev/ttyACM3 \ +
+ +
+Recording + + +```bash +lerobot-record \ + --robot.type=dk1_follower \ + --robot.port=/dev/tty.usbmodem00000000050C1 \ + --robot.joint_velocity_scaling=1.0 \ + --robot.cameras="{ + context: {type: opencv, index_or_path: 0, width: 640, height: 360, fps: 30}, + wrist: {type: opencv, index_or_path: 1, width: 640, height: 360, fps: 30} + }" \ + --teleop.type=dk1_leader \ + --teleop.port=/dev/tty.usbmodem58FA0824311 \ + --display_data=true \ + --dataset.repo_id=$USER/my_dataset \ + --dataset.push_to_hub=false \ + --dataset.num_episodes=50 \ + --dataset.episode_time_s=30 \ + --dataset.reset_time_s=15 \ + --dataset.single_task="My task description." +``` +```bash + --resume=true +``` +
+ +
+Inference + + +```bash +lerobot-record \ + --robot.type=dk1_follower \ + --robot.port=/dev/tty.usbmodem00000000050C1 \ + --robot.joint_velocity_scaling=0.5 \ + --robot.cameras="{ + context: {type: opencv, index_or_path: 0, width: 640, height: 360, fps: 30}, + wrist: {type: opencv, index_or_path: 1, width: 640, height: 360, fps: 30} + }" + --display_data=true \ + --dataset.repo_id=$USER/eval_my_model \ + --dataset.single_task="My task description." \ + --dataset.push_to_hub=false \ + --policy.path=outputs/my_model/checkpoints/last/pretrained_model +``` +
+ +
+Bimanual Teleoperation + + +```bash +lerobot-teleoperate \ + --robot.type=bi_dk1_follower \ + --robot.right_arm_port=/dev/ttyACM2 \ + --robot.left_arm_port=/dev/ttyACM1 \ + --robot.joint_velocity_scaling=0.1 \ + --teleop.type=bi_dk1_leader \ + --teleop.right_arm_port=/dev/ttyACM0 \ + --teleop.left_arm_port=/dev/ttyACM3 +``` +
+ +
+Bimanual Recording + + +```bash +lerobot-record \ + --robot.type=bi_dk1_follower \ + --robot.right_arm_port=/dev/ttyACM1 \ + --robot.left_arm_port=/dev/ttyACM0 \ + --robot.joint_velocity_scaling=1.0 \ + --robot.cameras="{ + context: {type: opencv, index_or_path: 2, width: 640, height: 360, fps: 15}, + right_wrist: {type: opencv, index_or_path: 4, width: 640, height: 360, fps: 30}, + left_wrist: {type: opencv, index_or_path: 0, width: 640, height: 360, fps: 30}, + }" \ + --teleop.type=bi_dk1_leader \ + --teleop.right_arm_port=/dev/ttyACM3 \ + --teleop.left_arm_port=/dev/ttyACM2 \ + --dataset.repo_id=qualiaadmin/spoon_35 \ + --dataset.push_to_hub=false \ + --dataset.num_episodes=40 \ + --dataset.episode_time_s=10 \ + --dataset.reset_time_s=0 \ + --dataset.single_task="Pick up spoon" \ + --dataset.reset_time_s=5 \ + --resume=false +``` +
+ + + +## Acknowledgements + +- [GELLO](https://wuphilipp.github.io/gello_site/) by Philipp Wu et al. +- [Low-Cost Robot Arm](https://github.com/AlexanderKoch-Koch/low_cost_robot) by Alexander Koch +- [LeRobot](https://github.com/huggingface/lerobot) by HuggingFace, Inc. +- [SO-100](https://github.com/TheRobotStudio/SO-ARM100) by TheRobotStudio +- [OpenArm](https://openarm.dev/) by Enactic, Inc. diff --git a/discord-0.0.119 (3).deb b/discord-0.0.119 (3).deb new file mode 100644 index 0000000000000000000000000000000000000000..7ea0ad445f9461eb408b14de0f955d58402087f1 --- /dev/null +++ b/discord-0.0.119 (3).deb @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:47aa2ef2ec2279ec0f014f6fdc43db1af6f03f9e107d9814bb88603d9e8d2463 +size 108129318 diff --git a/examples/bi_teleop.py b/examples/bi_teleop.py new file mode 100644 index 0000000000000000000000000000000000000000..843ee5d918837f38bb883e25c5c36b3cbf3fd0dc --- /dev/null +++ b/examples/bi_teleop.py @@ -0,0 +1,40 @@ +from trlc_dk1.bi_follower import BiDK1Follower, BiDK1FollowerConfig +from trlc_dk1.bi_leader import BiDK1Leader, BiDK1LeaderConfig +import time +import logging + +from lerobot.utils.utils import init_logging + +logger = logging.getLogger(__name__) +logger.setLevel(logging.DEBUG) + +init_logging() + +follower_config = BiDK1FollowerConfig( + left_arm_port="/dev/ttyACM1", + right_arm_port="/dev/ttyACM0", + joint_velocity_scaling=0.2, +) + +leader_config = BiDK1LeaderConfig( + left_arm_port="/dev/ttyACM3", + right_arm_port="/dev/ttyACM2", +) + +leader = BiDK1Leader(leader_config) +leader.connect() + +follower = BiDK1Follower(follower_config) +follower.connect() + +freq = 200 # Hz + +try: + while True: + action = leader.get_action() + follower.send_action(action) + time.sleep(1/freq) +except KeyboardInterrupt: + print("\nStopping teleop...") + leader.disconnect() + follower.disconnect() diff --git a/examples/calibration_follower.py b/examples/calibration_follower.py new file mode 100644 index 0000000000000000000000000000000000000000..c30c3c5d5b2029a43b86cc39adce33772ab5f293 --- /dev/null +++ b/examples/calibration_follower.py @@ -0,0 +1,32 @@ +from trlc_dk1.follower import DK1Follower, DK1FollowerConfig +from trlc_dk1.motors.DM_Control_Python.DM_CAN import * + +import serial +import time + + +follower_config = DK1FollowerConfig( + port="/dev/tty.usbmodem00000000050C1", +) +follower = DK1Follower(follower_config) + +follower.serial_device = serial.Serial(follower_config.port, 921600, timeout=0.5) +time.sleep(0.5) +follower.control = MotorControl(follower.serial_device) + +for key, motor in follower.motors.items(): + follower.control.addMotor(motor) + for _ in range(3): + follower.control.refresh_motor_status(motor) + time.sleep(0.01) + + if follower.control.read_motor_param(motor, DM_variable.CTRL_MODE) is not None: + print(f"{key} ({motor.MotorType.name}) is connected.") + else: + raise Exception(f"Unable to read from {key} ({motor.MotorType.name}).") + +for key, motor in follower.motors.items(): + follower.control.set_zero_position(motor) + print(f"{key} ({motor.MotorType.name}) set to zero position.") + +follower.control.serial_.close() \ No newline at end of file diff --git a/examples/calibration_leader.ipynb b/examples/calibration_leader.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..02c9b25a0b234ce6861600012161258751e4eb97 --- /dev/null +++ b/examples/calibration_leader.ipynb @@ -0,0 +1,133 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 55, + "id": "ccb98fb3", + "metadata": {}, + "outputs": [], + "source": [ + "from trlc_dk1.leader import DK1Leader, DK1LeaderConfig\n", + "\n", + "leader_config = DK1LeaderConfig(\n", + " port=\"/dev/tty.usbmodem5A680096411\"\n", + ")\n", + "\n", + "leader = DK1Leader(leader_config)\n", + "leader.connect()\n", + "leader.bus.write(\"Torque_Enable\", \"gripper\", 0, normalize=False)\n", + "leader.bus.sync_write(\"Homing_Offset\", 0, normalize=False)\n" + ] + }, + { + "cell_type": "markdown", + "id": "3cc733ce", + "metadata": {}, + "source": [ + "# PLACE LEADER IN RESTING POSITION" + ] + }, + { + "cell_type": "code", + "execution_count": 56, + "id": "e2752924", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "joint_2: Position: 2038, Offset: 10\n", + "joint_3: Position: 2027, Offset: 21\n", + "joint_4: Position: 2023, Offset: 25\n" + ] + }, + { + "data": { + "text/plain": [ + "{'joint_1': 0,\n", + " 'joint_2': 10,\n", + " 'joint_3': 21,\n", + " 'joint_4': 25,\n", + " 'joint_5': 0,\n", + " 'joint_6': 0,\n", + " 'gripper': 0}" + ] + }, + "execution_count": 56, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "joints_to_calibrate = [\"joint_2\", \"joint_3\", \"joint_4\"]\n", + "theoretical_zero_position = {\"joint_2\": 2048, \"joint_3\": 2048, \"joint_4\": 2048}\n", + "\n", + "for joint in joints_to_calibrate:\n", + " position = leader.bus.read(\"Present_Position\", joint, normalize=False)\n", + " offset = theoretical_zero_position[joint] - position\n", + " print(f\"{joint}: Position: {position}, Offset: {offset}\")\n", + " leader.bus.write(\"Homing_Offset\", joint, offset, normalize=False)\n", + "\n", + "leader.bus.sync_read(\"Homing_Offset\", normalize=False)" + ] + }, + { + "cell_type": "code", + "execution_count": 57, + "id": "8a1a3414", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "{'joint_1': 2029, 'joint_2': 2047, 'joint_3': 2048, 'joint_4': 2048, 'joint_5': 2031, 'joint_6': 1885, 'gripper': 2245}\n" + ] + } + ], + "source": [ + "print(leader.bus.sync_read(normalize=False, data_name=\"Present_Position\"))\n" + ] + }, + { + "cell_type": "code", + "execution_count": 58, + "id": "94f63a40", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "{'joint_1.pos': -0.02914563496982714, 'joint_2.pos': -0.0015339807878858025, 'joint_3.pos': -0.0015339807878858025, 'joint_4.pos': 0.0, 'joint_5.pos': -0.026077673394055978, 'joint_6.pos': -0.2500388684253596, 'gripper.pos': 0.059016393442622994}\n" + ] + } + ], + "source": [ + "print(leader.get_action())" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "dk1", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.10.18" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/follower_read_position.py b/examples/follower_read_position.py new file mode 100644 index 0000000000000000000000000000000000000000..30442e21bd47c6f1b6ef6eca21283cf3e2722e4d --- /dev/null +++ b/examples/follower_read_position.py @@ -0,0 +1,23 @@ +from trlc_dk1.follower import DK1Follower, DK1FollowerConfig +from trlc_dk1.motors.DM_Control_Python.DM_CAN import * + +import time + +follower_config = DK1FollowerConfig( + port="/dev/tty.usbmodem00000000050C1", +) +follower = DK1Follower(follower_config) + +follower.connect() + +for key, motor in follower.motors.items(): + follower.control.disable(motor) + +try: + while True: + print(follower.get_observation()) + time.sleep(0.01) + +except KeyboardInterrupt: + print("\nStopping read position...") + follower.disconnect() diff --git a/examples/leader_test.py b/examples/leader_test.py new file mode 100644 index 0000000000000000000000000000000000000000..0e6872e360fac63a90507012aadc5b416696e8ce --- /dev/null +++ b/examples/leader_test.py @@ -0,0 +1,15 @@ +from trlc_dk1.leader import DK1Leader, DK1LeaderConfig +import time + +leader_config = DK1LeaderConfig( + port="/dev/tty.usbmodem5A460819651" +) + +leader = DK1Leader(leader_config) +leader.connect() + + +while True: + action = leader.get_action() + print(action) + time.sleep(0.02) \ No newline at end of file diff --git a/examples/obs.py b/examples/obs.py new file mode 100644 index 0000000000000000000000000000000000000000..51c3fdda1b5dba40b28620cbff4039d904b42f83 --- /dev/null +++ b/examples/obs.py @@ -0,0 +1,15 @@ +# Get an observation and print its structure +obs = robot.get_observation() + +# See what type it is +print(type(obs)) + +# If it's a dictionary, print the keys +print(obs.keys()) + +# Print the full observation to see the structure +print(obs) + +# Or for a nicer view +import pprint +pprint.pprint(obs) \ No newline at end of file diff --git a/examples/read_motor_params.py b/examples/read_motor_params.py new file mode 100644 index 0000000000000000000000000000000000000000..580a532d1ad802011a7101f4c7001dd5ecb5747a --- /dev/null +++ b/examples/read_motor_params.py @@ -0,0 +1,21 @@ +from trlc_dk1.motors.DM_Control_Python.DM_CAN import * +import serial +import time + +motor=Motor(DM_Motor_Type.DM4340, 0x07, 0x17) + +serial_device = serial.Serial('/dev/tty.usbmodem00000000050C1', 921600, timeout=0.5) +time.sleep(0.5) + +control=MotorControl(serial_device) +control.addMotor(motor) + +if control.read_motor_param(motor, DM_variable.CTRL_MODE) is not None: + print("Motor is connected.") +else: + raise Exception("Unable to read motor parameters.") + + +for param in DM_variable: + value = control.read_motor_param(motor, param) + print(f"{param.name:<9} : {value}") \ No newline at end of file diff --git a/examples/teleop.py b/examples/teleop.py new file mode 100644 index 0000000000000000000000000000000000000000..85285e82ee0e7a15097cae6e4c7303278008dc4b --- /dev/null +++ b/examples/teleop.py @@ -0,0 +1,31 @@ +from trlc_dk1.follower import DK1Follower, DK1FollowerConfig +from trlc_dk1.leader import DK1Leader, DK1LeaderConfig +import time + + +follower_config = DK1FollowerConfig( + port="/dev/tty.usbmodem00000000050C1", + joint_velocity_scaling=0.2, +) + +leader_config = DK1LeaderConfig( + port="/dev/tty.usbmodem5A680096411" +) + +leader = DK1Leader(leader_config) +leader.connect() + +follower = DK1Follower(follower_config) +follower.connect() + +freq = 200 # Hz + +try: + while True: + action = leader.get_action() + follower.send_action(action) + time.sleep(1/freq) +except KeyboardInterrupt: + print("\nStopping teleop...") + leader.disconnect() + follower.disconnect() diff --git a/examples/uvc_cam_test.py b/examples/uvc_cam_test.py new file mode 100644 index 0000000000000000000000000000000000000000..52c682a6025e7b6c0e7e066017b234ea95fd4937 --- /dev/null +++ b/examples/uvc_cam_test.py @@ -0,0 +1,27 @@ +import cv2 + +def main(): + cam_index = 0 # Change this if your camera is not at index 0 + cap = cv2.VideoCapture(cam_index) + + if not cap.isOpened(): + print(f"Cannot open camera at index {cam_index}") + return + + print("Press 'q' to quit.") + while True: + ret, frame = cap.read() + if not ret: + print("Failed to grab frame") + break + + cv2.imshow('USB Camera Test', frame) + + if cv2.waitKey(1) & 0xFF == ord('q'): + break + + cap.release() + cv2.destroyAllWindows() + +if __name__ == "__main__": + main() diff --git a/hardware/TRLC-DK1-Follower_v0.2.0.step b/hardware/TRLC-DK1-Follower_v0.2.0.step new file mode 100644 index 0000000000000000000000000000000000000000..78f390964755c0e4b6348aa304b4888bd1483bf7 --- /dev/null +++ b/hardware/TRLC-DK1-Follower_v0.2.0.step @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:872b55aaf50b2545515ed6d9442555d13e3208cb4ace6874a05fc24ca090cf98 +size 44238541 diff --git a/hardware/follower_STEPs/link0-1_v0.2.0.step b/hardware/follower_STEPs/link0-1_v0.2.0.step new file mode 100644 index 0000000000000000000000000000000000000000..c51b1afd05302eedfa1318176d892ca39bea3ffc --- /dev/null +++ b/hardware/follower_STEPs/link0-1_v0.2.0.step @@ -0,0 +1,1620 @@ +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 */ 'link0-1_v0.2.0.step', +/* time_stamp */ '2025-10-08T20:55:39+02:00', +/* author */ (''), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v20.1', +/* originating_system */ 'Autodesk Translation Framework v14.17.0.0', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#1536); +#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#1543,#12); +#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#1535); +#13=STYLED_ITEM('',(#1552),#14); +#14=MANIFOLD_SOLID_BREP('Body1',#900); +#15=FACE_BOUND('',#132,.T.); +#16=FACE_BOUND('',#133,.T.); +#17=FACE_BOUND('',#135,.T.); +#18=FACE_BOUND('',#136,.T.); +#19=FACE_BOUND('',#139,.T.); +#20=FACE_BOUND('',#140,.T.); +#21=FACE_BOUND('',#142,.T.); +#22=FACE_BOUND('',#143,.T.); +#23=FACE_BOUND('',#157,.T.); +#24=FACE_BOUND('',#158,.T.); +#25=FACE_BOUND('',#159,.T.); +#26=FACE_BOUND('',#160,.T.); +#27=FACE_BOUND('',#161,.T.); +#28=FACE_BOUND('',#162,.T.); +#29=FACE_BOUND('',#163,.T.); +#30=FACE_BOUND('',#171,.T.); +#31=FACE_BOUND('',#172,.T.); +#32=FACE_BOUND('',#173,.T.); +#33=FACE_BOUND('',#174,.T.); +#34=FACE_BOUND('',#175,.T.); +#35=FACE_BOUND('',#176,.T.); +#36=FACE_BOUND('',#177,.T.); +#37=PLANE('',#929); +#38=PLANE('',#939); +#39=PLANE('',#940); +#40=PLANE('',#941); +#41=PLANE('',#942); +#42=PLANE('',#943); +#43=PLANE('',#944); +#44=PLANE('',#945); +#45=PLANE('',#970); +#46=PLANE('',#974); +#47=PLANE('',#978); +#48=PLANE('',#985); +#49=PLANE('',#989); +#50=PLANE('',#993); +#51=PLANE('',#997); +#52=PLANE('',#998); +#53=PLANE('',#999); +#54=PLANE('',#1000); +#55=PLANE('',#1001); +#56=PLANE('',#1002); +#57=PLANE('',#1003); +#58=PLANE('',#1004); +#59=PLANE('',#1005); +#60=PLANE('',#1006); +#61=PLANE('',#1007); +#62=PLANE('',#1008); +#63=PLANE('',#1009); +#64=PLANE('',#1010); +#65=PLANE('',#1011); +#66=PLANE('',#1012); +#67=FACE_OUTER_BOUND('',#120,.T.); +#68=FACE_OUTER_BOUND('',#121,.T.); +#69=FACE_OUTER_BOUND('',#122,.T.); +#70=FACE_OUTER_BOUND('',#123,.T.); +#71=FACE_OUTER_BOUND('',#124,.T.); +#72=FACE_OUTER_BOUND('',#125,.T.); +#73=FACE_OUTER_BOUND('',#126,.T.); +#74=FACE_OUTER_BOUND('',#127,.T.); +#75=FACE_OUTER_BOUND('',#128,.T.); +#76=FACE_OUTER_BOUND('',#129,.T.); +#77=FACE_OUTER_BOUND('',#130,.T.); +#78=FACE_OUTER_BOUND('',#131,.T.); +#79=FACE_OUTER_BOUND('',#134,.T.); +#80=FACE_OUTER_BOUND('',#137,.T.); +#81=FACE_OUTER_BOUND('',#138,.T.); +#82=FACE_OUTER_BOUND('',#141,.T.); +#83=FACE_OUTER_BOUND('',#144,.T.); +#84=FACE_OUTER_BOUND('',#145,.T.); +#85=FACE_OUTER_BOUND('',#146,.T.); +#86=FACE_OUTER_BOUND('',#147,.T.); +#87=FACE_OUTER_BOUND('',#148,.T.); +#88=FACE_OUTER_BOUND('',#149,.T.); +#89=FACE_OUTER_BOUND('',#150,.T.); +#90=FACE_OUTER_BOUND('',#151,.T.); +#91=FACE_OUTER_BOUND('',#152,.T.); +#92=FACE_OUTER_BOUND('',#153,.T.); +#93=FACE_OUTER_BOUND('',#154,.T.); +#94=FACE_OUTER_BOUND('',#155,.T.); +#95=FACE_OUTER_BOUND('',#156,.T.); +#96=FACE_OUTER_BOUND('',#164,.T.); +#97=FACE_OUTER_BOUND('',#165,.T.); +#98=FACE_OUTER_BOUND('',#166,.T.); +#99=FACE_OUTER_BOUND('',#167,.T.); +#100=FACE_OUTER_BOUND('',#168,.T.); +#101=FACE_OUTER_BOUND('',#169,.T.); +#102=FACE_OUTER_BOUND('',#170,.T.); +#103=FACE_OUTER_BOUND('',#178,.T.); +#104=FACE_OUTER_BOUND('',#179,.T.); +#105=FACE_OUTER_BOUND('',#180,.T.); +#106=FACE_OUTER_BOUND('',#181,.T.); +#107=FACE_OUTER_BOUND('',#182,.T.); +#108=FACE_OUTER_BOUND('',#183,.T.); +#109=FACE_OUTER_BOUND('',#184,.T.); +#110=FACE_OUTER_BOUND('',#185,.T.); +#111=FACE_OUTER_BOUND('',#186,.T.); +#112=FACE_OUTER_BOUND('',#187,.T.); +#113=FACE_OUTER_BOUND('',#188,.T.); +#114=FACE_OUTER_BOUND('',#189,.T.); +#115=FACE_OUTER_BOUND('',#190,.T.); +#116=FACE_OUTER_BOUND('',#191,.T.); +#117=FACE_OUTER_BOUND('',#192,.T.); +#118=FACE_OUTER_BOUND('',#193,.T.); +#119=FACE_OUTER_BOUND('',#194,.T.); +#120=EDGE_LOOP('',(#582,#583,#584,#585)); +#121=EDGE_LOOP('',(#586,#587,#588,#589)); +#122=EDGE_LOOP('',(#590,#591,#592,#593)); +#123=EDGE_LOOP('',(#594,#595,#596,#597)); +#124=EDGE_LOOP('',(#598,#599,#600,#601)); +#125=EDGE_LOOP('',(#602,#603,#604,#605)); +#126=EDGE_LOOP('',(#606,#607,#608,#609)); +#127=EDGE_LOOP('',(#610,#611,#612,#613)); +#128=EDGE_LOOP('',(#614,#615,#616,#617)); +#129=EDGE_LOOP('',(#618,#619,#620,#621)); +#130=EDGE_LOOP('',(#622,#623,#624,#625)); +#131=EDGE_LOOP('',(#626,#627,#628,#629,#630,#631)); +#132=EDGE_LOOP('',(#632)); +#133=EDGE_LOOP('',(#633)); +#134=EDGE_LOOP('',(#634,#635,#636,#637,#638,#639)); +#135=EDGE_LOOP('',(#640)); +#136=EDGE_LOOP('',(#641)); +#137=EDGE_LOOP('',(#642,#643,#644,#645)); +#138=EDGE_LOOP('',(#646,#647,#648,#649,#650,#651)); +#139=EDGE_LOOP('',(#652)); +#140=EDGE_LOOP('',(#653)); +#141=EDGE_LOOP('',(#654,#655,#656,#657,#658,#659)); +#142=EDGE_LOOP('',(#660)); +#143=EDGE_LOOP('',(#661)); +#144=EDGE_LOOP('',(#662,#663,#664,#665)); +#145=EDGE_LOOP('',(#666,#667,#668,#669)); +#146=EDGE_LOOP('',(#670,#671,#672,#673)); +#147=EDGE_LOOP('',(#674,#675,#676,#677)); +#148=EDGE_LOOP('',(#678,#679,#680,#681)); +#149=EDGE_LOOP('',(#682,#683,#684,#685)); +#150=EDGE_LOOP('',(#686,#687,#688,#689)); +#151=EDGE_LOOP('',(#690,#691,#692,#693)); +#152=EDGE_LOOP('',(#694,#695,#696,#697)); +#153=EDGE_LOOP('',(#698,#699,#700,#701)); +#154=EDGE_LOOP('',(#702,#703,#704,#705)); +#155=EDGE_LOOP('',(#706,#707,#708,#709)); +#156=EDGE_LOOP('',(#710,#711,#712,#713)); +#157=EDGE_LOOP('',(#714)); +#158=EDGE_LOOP('',(#715)); +#159=EDGE_LOOP('',(#716)); +#160=EDGE_LOOP('',(#717)); +#161=EDGE_LOOP('',(#718)); +#162=EDGE_LOOP('',(#719)); +#163=EDGE_LOOP('',(#720)); +#164=EDGE_LOOP('',(#721,#722,#723,#724)); +#165=EDGE_LOOP('',(#725,#726,#727,#728)); +#166=EDGE_LOOP('',(#729,#730,#731,#732)); +#167=EDGE_LOOP('',(#733,#734,#735,#736)); +#168=EDGE_LOOP('',(#737,#738,#739,#740)); +#169=EDGE_LOOP('',(#741,#742,#743,#744)); +#170=EDGE_LOOP('',(#745,#746,#747,#748)); +#171=EDGE_LOOP('',(#749)); +#172=EDGE_LOOP('',(#750)); +#173=EDGE_LOOP('',(#751)); +#174=EDGE_LOOP('',(#752)); +#175=EDGE_LOOP('',(#753)); +#176=EDGE_LOOP('',(#754)); +#177=EDGE_LOOP('',(#755)); +#178=EDGE_LOOP('',(#756,#757,#758,#759)); +#179=EDGE_LOOP('',(#760,#761,#762,#763)); +#180=EDGE_LOOP('',(#764,#765,#766,#767)); +#181=EDGE_LOOP('',(#768,#769,#770,#771)); +#182=EDGE_LOOP('',(#772,#773,#774,#775)); +#183=EDGE_LOOP('',(#776,#777,#778,#779)); +#184=EDGE_LOOP('',(#780,#781,#782,#783)); +#185=EDGE_LOOP('',(#784,#785,#786,#787)); +#186=EDGE_LOOP('',(#788,#789,#790,#791)); +#187=EDGE_LOOP('',(#792,#793,#794,#795)); +#188=EDGE_LOOP('',(#796,#797,#798,#799)); +#189=EDGE_LOOP('',(#800,#801,#802,#803)); +#190=EDGE_LOOP('',(#804,#805,#806,#807)); +#191=EDGE_LOOP('',(#808,#809,#810,#811)); +#192=EDGE_LOOP('',(#812,#813,#814,#815)); +#193=EDGE_LOOP('',(#816,#817,#818,#819)); +#194=EDGE_LOOP('',(#820,#821,#822,#823)); +#195=LINE('',#1293,#270); +#196=LINE('',#1299,#271); +#197=LINE('',#1305,#272); +#198=LINE('',#1311,#273); +#199=LINE('',#1318,#274); +#200=LINE('',#1321,#275); +#201=LINE('',#1324,#276); +#202=LINE('',#1326,#277); +#203=LINE('',#1327,#278); +#204=LINE('',#1333,#279); +#205=LINE('',#1339,#280); +#206=LINE('',#1342,#281); +#207=LINE('',#1348,#282); +#208=LINE('',#1351,#283); +#209=LINE('',#1353,#284); +#210=LINE('',#1354,#285); +#211=LINE('',#1357,#286); +#212=LINE('',#1359,#287); +#213=LINE('',#1360,#288); +#214=LINE('',#1363,#289); +#215=LINE('',#1364,#290); +#216=LINE('',#1367,#291); +#217=LINE('',#1369,#292); +#218=LINE('',#1370,#293); +#219=LINE('',#1373,#294); +#220=LINE('',#1374,#295); +#221=LINE('',#1376,#296); +#222=LINE('',#1379,#297); +#223=LINE('',#1381,#298); +#224=LINE('',#1382,#299); +#225=LINE('',#1387,#300); +#226=LINE('',#1393,#301); +#227=LINE('',#1399,#302); +#228=LINE('',#1405,#303); +#229=LINE('',#1411,#304); +#230=LINE('',#1417,#305); +#231=LINE('',#1423,#306); +#232=LINE('',#1430,#307); +#233=LINE('',#1433,#308); +#234=LINE('',#1435,#309); +#235=LINE('',#1436,#310); +#236=LINE('',#1441,#311); +#237=LINE('',#1445,#312); +#238=LINE('',#1447,#313); +#239=LINE('',#1448,#314); +#240=LINE('',#1454,#315); +#241=LINE('',#1457,#316); +#242=LINE('',#1459,#317); +#243=LINE('',#1460,#318); +#244=LINE('',#1468,#319); +#245=LINE('',#1472,#320); +#246=LINE('',#1474,#321); +#247=LINE('',#1475,#322); +#248=LINE('',#1481,#323); +#249=LINE('',#1484,#324); +#250=LINE('',#1486,#325); +#251=LINE('',#1487,#326); +#252=LINE('',#1492,#327); +#253=LINE('',#1496,#328); +#254=LINE('',#1498,#329); +#255=LINE('',#1499,#330); +#256=LINE('',#1504,#331); +#257=LINE('',#1505,#332); +#258=LINE('',#1507,#333); +#259=LINE('',#1508,#334); +#260=LINE('',#1510,#335); +#261=LINE('',#1512,#336); +#262=LINE('',#1516,#337); +#263=LINE('',#1518,#338); +#264=LINE('',#1520,#339); +#265=LINE('',#1522,#340); +#266=LINE('',#1524,#341); +#267=LINE('',#1526,#342); +#268=LINE('',#1528,#343); +#269=LINE('',#1530,#344); +#270=VECTOR('',#1019,2.65); +#271=VECTOR('',#1026,2.65); +#272=VECTOR('',#1033,2.65); +#273=VECTOR('',#1040,2.65); +#274=VECTOR('',#1047,10.); +#275=VECTOR('',#1050,10.); +#276=VECTOR('',#1053,10.); +#277=VECTOR('',#1054,10.); +#278=VECTOR('',#1055,10.); +#279=VECTOR('',#1062,10.); +#280=VECTOR('',#1067,10.); +#281=VECTOR('',#1070,10.); +#282=VECTOR('',#1075,10.); +#283=VECTOR('',#1078,10.); +#284=VECTOR('',#1081,10.); +#285=VECTOR('',#1082,10.); +#286=VECTOR('',#1085,10.); +#287=VECTOR('',#1086,10.); +#288=VECTOR('',#1087,10.); +#289=VECTOR('',#1090,10.); +#290=VECTOR('',#1091,10.); +#291=VECTOR('',#1094,10.); +#292=VECTOR('',#1095,10.); +#293=VECTOR('',#1096,10.); +#294=VECTOR('',#1099,10.); +#295=VECTOR('',#1100,10.); +#296=VECTOR('',#1103,10.); +#297=VECTOR('',#1106,10.); +#298=VECTOR('',#1107,10.); +#299=VECTOR('',#1108,10.); +#300=VECTOR('',#1113,1.6); +#301=VECTOR('',#1120,1.6); +#302=VECTOR('',#1127,1.6); +#303=VECTOR('',#1134,1.6); +#304=VECTOR('',#1141,1.6); +#305=VECTOR('',#1148,1.6); +#306=VECTOR('',#1155,21.5); +#307=VECTOR('',#1164,10.); +#308=VECTOR('',#1167,10.); +#309=VECTOR('',#1168,10.); +#310=VECTOR('',#1169,10.); +#311=VECTOR('',#1174,10.); +#312=VECTOR('',#1179,10.); +#313=VECTOR('',#1180,10.); +#314=VECTOR('',#1181,10.); +#315=VECTOR('',#1188,10.); +#316=VECTOR('',#1191,10.); +#317=VECTOR('',#1192,10.); +#318=VECTOR('',#1193,10.); +#319=VECTOR('',#1204,10.); +#320=VECTOR('',#1209,10.); +#321=VECTOR('',#1210,10.); +#322=VECTOR('',#1211,10.); +#323=VECTOR('',#1218,10.); +#324=VECTOR('',#1221,10.); +#325=VECTOR('',#1222,10.); +#326=VECTOR('',#1223,10.); +#327=VECTOR('',#1228,10.); +#328=VECTOR('',#1233,10.); +#329=VECTOR('',#1234,10.); +#330=VECTOR('',#1235,10.); +#331=VECTOR('',#1244,10.); +#332=VECTOR('',#1245,10.); +#333=VECTOR('',#1248,10.); +#334=VECTOR('',#1249,10.); +#335=VECTOR('',#1252,10.); +#336=VECTOR('',#1255,10.); +#337=VECTOR('',#1262,10.); +#338=VECTOR('',#1265,10.); +#339=VECTOR('',#1268,10.); +#340=VECTOR('',#1271,10.); +#341=VECTOR('',#1274,10.); +#342=VECTOR('',#1277,10.); +#343=VECTOR('',#1280,10.); +#344=VECTOR('',#1283,10.); +#345=CIRCLE('',#915,2.65); +#346=CIRCLE('',#916,2.65); +#347=CIRCLE('',#918,2.65); +#348=CIRCLE('',#919,2.65); +#349=CIRCLE('',#921,2.65); +#350=CIRCLE('',#922,2.65); +#351=CIRCLE('',#924,2.65); +#352=CIRCLE('',#925,2.65); +#353=CIRCLE('',#927,8.50235261560071); +#354=CIRCLE('',#928,8.50235261560071); +#355=CIRCLE('',#931,8.50235261560071); +#356=CIRCLE('',#932,8.50235261560071); +#357=CIRCLE('',#934,8.50235261560071); +#358=CIRCLE('',#935,8.50235261560071); +#359=CIRCLE('',#937,8.50235261560071); +#360=CIRCLE('',#938,8.50235261560071); +#361=CIRCLE('',#947,1.6); +#362=CIRCLE('',#948,1.6); +#363=CIRCLE('',#950,1.6); +#364=CIRCLE('',#951,1.6); +#365=CIRCLE('',#953,1.6); +#366=CIRCLE('',#954,1.6); +#367=CIRCLE('',#956,1.6); +#368=CIRCLE('',#957,1.6); +#369=CIRCLE('',#959,1.6); +#370=CIRCLE('',#960,1.6); +#371=CIRCLE('',#962,1.6); +#372=CIRCLE('',#963,1.6); +#373=CIRCLE('',#965,21.5); +#374=CIRCLE('',#966,21.5); +#375=CIRCLE('',#968,0.100000000000002); +#376=CIRCLE('',#969,0.100000000000002); +#377=CIRCLE('',#972,0.100000000000002); +#378=CIRCLE('',#973,0.100000000000002); +#379=CIRCLE('',#976,2.6); +#380=CIRCLE('',#977,2.6); +#381=CIRCLE('',#980,2.6); +#382=CIRCLE('',#981,2.6); +#383=CIRCLE('',#983,2.6); +#384=CIRCLE('',#984,2.6); +#385=CIRCLE('',#987,2.6); +#386=CIRCLE('',#988,2.6); +#387=CIRCLE('',#991,0.1); +#388=CIRCLE('',#992,0.1); +#389=CIRCLE('',#995,0.1); +#390=CIRCLE('',#996,0.1); +#391=VERTEX_POINT('',#1290); +#392=VERTEX_POINT('',#1292); +#393=VERTEX_POINT('',#1296); +#394=VERTEX_POINT('',#1298); +#395=VERTEX_POINT('',#1302); +#396=VERTEX_POINT('',#1304); +#397=VERTEX_POINT('',#1308); +#398=VERTEX_POINT('',#1310); +#399=VERTEX_POINT('',#1314); +#400=VERTEX_POINT('',#1315); +#401=VERTEX_POINT('',#1317); +#402=VERTEX_POINT('',#1319); +#403=VERTEX_POINT('',#1323); +#404=VERTEX_POINT('',#1325); +#405=VERTEX_POINT('',#1329); +#406=VERTEX_POINT('',#1331); +#407=VERTEX_POINT('',#1335); +#408=VERTEX_POINT('',#1336); +#409=VERTEX_POINT('',#1338); +#410=VERTEX_POINT('',#1340); +#411=VERTEX_POINT('',#1344); +#412=VERTEX_POINT('',#1345); +#413=VERTEX_POINT('',#1347); +#414=VERTEX_POINT('',#1349); +#415=VERTEX_POINT('',#1356); +#416=VERTEX_POINT('',#1358); +#417=VERTEX_POINT('',#1362); +#418=VERTEX_POINT('',#1366); +#419=VERTEX_POINT('',#1368); +#420=VERTEX_POINT('',#1372); +#421=VERTEX_POINT('',#1378); +#422=VERTEX_POINT('',#1380); +#423=VERTEX_POINT('',#1384); +#424=VERTEX_POINT('',#1386); +#425=VERTEX_POINT('',#1390); +#426=VERTEX_POINT('',#1392); +#427=VERTEX_POINT('',#1396); +#428=VERTEX_POINT('',#1398); +#429=VERTEX_POINT('',#1402); +#430=VERTEX_POINT('',#1404); +#431=VERTEX_POINT('',#1408); +#432=VERTEX_POINT('',#1410); +#433=VERTEX_POINT('',#1414); +#434=VERTEX_POINT('',#1416); +#435=VERTEX_POINT('',#1420); +#436=VERTEX_POINT('',#1422); +#437=VERTEX_POINT('',#1426); +#438=VERTEX_POINT('',#1428); +#439=VERTEX_POINT('',#1432); +#440=VERTEX_POINT('',#1434); +#441=VERTEX_POINT('',#1438); +#442=VERTEX_POINT('',#1440); +#443=VERTEX_POINT('',#1444); +#444=VERTEX_POINT('',#1446); +#445=VERTEX_POINT('',#1450); +#446=VERTEX_POINT('',#1452); +#447=VERTEX_POINT('',#1456); +#448=VERTEX_POINT('',#1458); +#449=VERTEX_POINT('',#1465); +#450=VERTEX_POINT('',#1467); +#451=VERTEX_POINT('',#1471); +#452=VERTEX_POINT('',#1473); +#453=VERTEX_POINT('',#1477); +#454=VERTEX_POINT('',#1479); +#455=VERTEX_POINT('',#1483); +#456=VERTEX_POINT('',#1485); +#457=VERTEX_POINT('',#1489); +#458=VERTEX_POINT('',#1491); +#459=VERTEX_POINT('',#1495); +#460=VERTEX_POINT('',#1497); +#461=EDGE_CURVE('',#391,#391,#345,.T.); +#462=EDGE_CURVE('',#391,#392,#195,.T.); +#463=EDGE_CURVE('',#392,#392,#346,.T.); +#464=EDGE_CURVE('',#393,#393,#347,.T.); +#465=EDGE_CURVE('',#393,#394,#196,.T.); +#466=EDGE_CURVE('',#394,#394,#348,.T.); +#467=EDGE_CURVE('',#395,#395,#349,.T.); +#468=EDGE_CURVE('',#395,#396,#197,.T.); +#469=EDGE_CURVE('',#396,#396,#350,.T.); +#470=EDGE_CURVE('',#397,#397,#351,.T.); +#471=EDGE_CURVE('',#397,#398,#198,.T.); +#472=EDGE_CURVE('',#398,#398,#352,.T.); +#473=EDGE_CURVE('',#399,#400,#353,.T.); +#474=EDGE_CURVE('',#401,#399,#199,.T.); +#475=EDGE_CURVE('',#402,#401,#354,.T.); +#476=EDGE_CURVE('',#402,#400,#200,.T.); +#477=EDGE_CURVE('',#400,#403,#201,.T.); +#478=EDGE_CURVE('',#404,#402,#202,.T.); +#479=EDGE_CURVE('',#404,#403,#203,.T.); +#480=EDGE_CURVE('',#403,#405,#355,.T.); +#481=EDGE_CURVE('',#406,#404,#356,.T.); +#482=EDGE_CURVE('',#405,#406,#204,.T.); +#483=EDGE_CURVE('',#407,#408,#357,.T.); +#484=EDGE_CURVE('',#409,#407,#205,.T.); +#485=EDGE_CURVE('',#410,#409,#358,.T.); +#486=EDGE_CURVE('',#408,#410,#206,.T.); +#487=EDGE_CURVE('',#411,#412,#359,.T.); +#488=EDGE_CURVE('',#413,#411,#207,.T.); +#489=EDGE_CURVE('',#414,#413,#360,.T.); +#490=EDGE_CURVE('',#414,#412,#208,.T.); +#491=EDGE_CURVE('',#412,#407,#209,.T.); +#492=EDGE_CURVE('',#409,#414,#210,.T.); +#493=EDGE_CURVE('',#415,#399,#211,.T.); +#494=EDGE_CURVE('',#415,#416,#212,.T.); +#495=EDGE_CURVE('',#416,#401,#213,.T.); +#496=EDGE_CURVE('',#405,#417,#214,.T.); +#497=EDGE_CURVE('',#417,#415,#215,.T.); +#498=EDGE_CURVE('',#418,#413,#216,.T.); +#499=EDGE_CURVE('',#419,#418,#217,.T.); +#500=EDGE_CURVE('',#410,#419,#218,.T.); +#501=EDGE_CURVE('',#406,#420,#219,.T.); +#502=EDGE_CURVE('',#417,#420,#220,.T.); +#503=EDGE_CURVE('',#420,#416,#221,.T.); +#504=EDGE_CURVE('',#408,#421,#222,.T.); +#505=EDGE_CURVE('',#421,#422,#223,.T.); +#506=EDGE_CURVE('',#422,#411,#224,.T.); +#507=EDGE_CURVE('',#423,#423,#361,.T.); +#508=EDGE_CURVE('',#423,#424,#225,.T.); +#509=EDGE_CURVE('',#424,#424,#362,.T.); +#510=EDGE_CURVE('',#425,#425,#363,.T.); +#511=EDGE_CURVE('',#425,#426,#226,.T.); +#512=EDGE_CURVE('',#426,#426,#364,.T.); +#513=EDGE_CURVE('',#427,#427,#365,.T.); +#514=EDGE_CURVE('',#427,#428,#227,.T.); +#515=EDGE_CURVE('',#428,#428,#366,.T.); +#516=EDGE_CURVE('',#429,#429,#367,.T.); +#517=EDGE_CURVE('',#429,#430,#228,.T.); +#518=EDGE_CURVE('',#430,#430,#368,.T.); +#519=EDGE_CURVE('',#431,#431,#369,.T.); +#520=EDGE_CURVE('',#431,#432,#229,.T.); +#521=EDGE_CURVE('',#432,#432,#370,.T.); +#522=EDGE_CURVE('',#433,#433,#371,.T.); +#523=EDGE_CURVE('',#433,#434,#230,.T.); +#524=EDGE_CURVE('',#434,#434,#372,.T.); +#525=EDGE_CURVE('',#435,#435,#373,.T.); +#526=EDGE_CURVE('',#435,#436,#231,.T.); +#527=EDGE_CURVE('',#436,#436,#374,.T.); +#528=EDGE_CURVE('',#437,#419,#375,.T.); +#529=EDGE_CURVE('',#418,#438,#376,.T.); +#530=EDGE_CURVE('',#438,#437,#232,.T.); +#531=EDGE_CURVE('',#439,#438,#233,.T.); +#532=EDGE_CURVE('',#440,#439,#234,.T.); +#533=EDGE_CURVE('',#437,#440,#235,.T.); +#534=EDGE_CURVE('',#416,#441,#377,.T.); +#535=EDGE_CURVE('',#441,#442,#236,.T.); +#536=EDGE_CURVE('',#442,#420,#378,.T.); +#537=EDGE_CURVE('',#443,#441,#237,.T.); +#538=EDGE_CURVE('',#444,#443,#238,.T.); +#539=EDGE_CURVE('',#442,#444,#239,.T.); +#540=EDGE_CURVE('',#445,#440,#379,.T.); +#541=EDGE_CURVE('',#439,#446,#380,.T.); +#542=EDGE_CURVE('',#446,#445,#240,.T.); +#543=EDGE_CURVE('',#447,#446,#241,.T.); +#544=EDGE_CURVE('',#448,#447,#242,.T.); +#545=EDGE_CURVE('',#445,#448,#243,.T.); +#546=EDGE_CURVE('',#443,#448,#381,.T.); +#547=EDGE_CURVE('',#447,#444,#382,.T.); +#548=EDGE_CURVE('',#449,#421,#383,.T.); +#549=EDGE_CURVE('',#450,#449,#244,.T.); +#550=EDGE_CURVE('',#422,#450,#384,.T.); +#551=EDGE_CURVE('',#449,#451,#245,.T.); +#552=EDGE_CURVE('',#451,#452,#246,.T.); +#553=EDGE_CURVE('',#452,#450,#247,.T.); +#554=EDGE_CURVE('',#415,#453,#385,.T.); +#555=EDGE_CURVE('',#454,#417,#386,.T.); +#556=EDGE_CURVE('',#453,#454,#248,.T.); +#557=EDGE_CURVE('',#454,#455,#249,.T.); +#558=EDGE_CURVE('',#455,#456,#250,.T.); +#559=EDGE_CURVE('',#456,#453,#251,.T.); +#560=EDGE_CURVE('',#457,#451,#387,.T.); +#561=EDGE_CURVE('',#458,#457,#252,.T.); +#562=EDGE_CURVE('',#452,#458,#388,.T.); +#563=EDGE_CURVE('',#457,#459,#253,.T.); +#564=EDGE_CURVE('',#459,#460,#254,.T.); +#565=EDGE_CURVE('',#460,#458,#255,.T.); +#566=EDGE_CURVE('',#456,#459,#389,.T.); +#567=EDGE_CURVE('',#460,#455,#390,.T.); +#568=EDGE_CURVE('',#421,#419,#256,.T.); +#569=EDGE_CURVE('',#449,#437,#257,.T.); +#570=EDGE_CURVE('',#450,#438,#258,.T.); +#571=EDGE_CURVE('',#422,#418,#259,.T.); +#572=EDGE_CURVE('',#452,#439,#260,.T.); +#573=EDGE_CURVE('',#451,#440,#261,.T.); +#574=EDGE_CURVE('',#453,#441,#262,.T.); +#575=EDGE_CURVE('',#454,#442,#263,.T.); +#576=EDGE_CURVE('',#456,#443,#264,.T.); +#577=EDGE_CURVE('',#455,#444,#265,.T.); +#578=EDGE_CURVE('',#457,#445,#266,.T.); +#579=EDGE_CURVE('',#458,#446,#267,.T.); +#580=EDGE_CURVE('',#460,#447,#268,.T.); +#581=EDGE_CURVE('',#459,#448,#269,.T.); +#582=ORIENTED_EDGE('',*,*,#461,.F.); +#583=ORIENTED_EDGE('',*,*,#462,.T.); +#584=ORIENTED_EDGE('',*,*,#463,.F.); +#585=ORIENTED_EDGE('',*,*,#462,.F.); +#586=ORIENTED_EDGE('',*,*,#464,.F.); +#587=ORIENTED_EDGE('',*,*,#465,.T.); +#588=ORIENTED_EDGE('',*,*,#466,.F.); +#589=ORIENTED_EDGE('',*,*,#465,.F.); +#590=ORIENTED_EDGE('',*,*,#467,.F.); +#591=ORIENTED_EDGE('',*,*,#468,.T.); +#592=ORIENTED_EDGE('',*,*,#469,.F.); +#593=ORIENTED_EDGE('',*,*,#468,.F.); +#594=ORIENTED_EDGE('',*,*,#470,.F.); +#595=ORIENTED_EDGE('',*,*,#471,.T.); +#596=ORIENTED_EDGE('',*,*,#472,.F.); +#597=ORIENTED_EDGE('',*,*,#471,.F.); +#598=ORIENTED_EDGE('',*,*,#473,.F.); +#599=ORIENTED_EDGE('',*,*,#474,.F.); +#600=ORIENTED_EDGE('',*,*,#475,.F.); +#601=ORIENTED_EDGE('',*,*,#476,.T.); +#602=ORIENTED_EDGE('',*,*,#477,.F.); +#603=ORIENTED_EDGE('',*,*,#476,.F.); +#604=ORIENTED_EDGE('',*,*,#478,.F.); +#605=ORIENTED_EDGE('',*,*,#479,.T.); +#606=ORIENTED_EDGE('',*,*,#480,.F.); +#607=ORIENTED_EDGE('',*,*,#479,.F.); +#608=ORIENTED_EDGE('',*,*,#481,.F.); +#609=ORIENTED_EDGE('',*,*,#482,.F.); +#610=ORIENTED_EDGE('',*,*,#483,.F.); +#611=ORIENTED_EDGE('',*,*,#484,.F.); +#612=ORIENTED_EDGE('',*,*,#485,.F.); +#613=ORIENTED_EDGE('',*,*,#486,.F.); +#614=ORIENTED_EDGE('',*,*,#487,.F.); +#615=ORIENTED_EDGE('',*,*,#488,.F.); +#616=ORIENTED_EDGE('',*,*,#489,.F.); +#617=ORIENTED_EDGE('',*,*,#490,.T.); +#618=ORIENTED_EDGE('',*,*,#491,.F.); +#619=ORIENTED_EDGE('',*,*,#490,.F.); +#620=ORIENTED_EDGE('',*,*,#492,.F.); +#621=ORIENTED_EDGE('',*,*,#484,.T.); +#622=ORIENTED_EDGE('',*,*,#474,.T.); +#623=ORIENTED_EDGE('',*,*,#493,.F.); +#624=ORIENTED_EDGE('',*,*,#494,.T.); +#625=ORIENTED_EDGE('',*,*,#495,.T.); +#626=ORIENTED_EDGE('',*,*,#473,.T.); +#627=ORIENTED_EDGE('',*,*,#477,.T.); +#628=ORIENTED_EDGE('',*,*,#480,.T.); +#629=ORIENTED_EDGE('',*,*,#496,.T.); +#630=ORIENTED_EDGE('',*,*,#497,.T.); +#631=ORIENTED_EDGE('',*,*,#493,.T.); +#632=ORIENTED_EDGE('',*,*,#466,.T.); +#633=ORIENTED_EDGE('',*,*,#469,.T.); +#634=ORIENTED_EDGE('',*,*,#485,.T.); +#635=ORIENTED_EDGE('',*,*,#492,.T.); +#636=ORIENTED_EDGE('',*,*,#489,.T.); +#637=ORIENTED_EDGE('',*,*,#498,.F.); +#638=ORIENTED_EDGE('',*,*,#499,.F.); +#639=ORIENTED_EDGE('',*,*,#500,.F.); +#640=ORIENTED_EDGE('',*,*,#461,.T.); +#641=ORIENTED_EDGE('',*,*,#470,.T.); +#642=ORIENTED_EDGE('',*,*,#482,.T.); +#643=ORIENTED_EDGE('',*,*,#501,.T.); +#644=ORIENTED_EDGE('',*,*,#502,.F.); +#645=ORIENTED_EDGE('',*,*,#496,.F.); +#646=ORIENTED_EDGE('',*,*,#475,.T.); +#647=ORIENTED_EDGE('',*,*,#495,.F.); +#648=ORIENTED_EDGE('',*,*,#503,.F.); +#649=ORIENTED_EDGE('',*,*,#501,.F.); +#650=ORIENTED_EDGE('',*,*,#481,.T.); +#651=ORIENTED_EDGE('',*,*,#478,.T.); +#652=ORIENTED_EDGE('',*,*,#464,.T.); +#653=ORIENTED_EDGE('',*,*,#467,.T.); +#654=ORIENTED_EDGE('',*,*,#483,.T.); +#655=ORIENTED_EDGE('',*,*,#504,.T.); +#656=ORIENTED_EDGE('',*,*,#505,.T.); +#657=ORIENTED_EDGE('',*,*,#506,.T.); +#658=ORIENTED_EDGE('',*,*,#487,.T.); +#659=ORIENTED_EDGE('',*,*,#491,.T.); +#660=ORIENTED_EDGE('',*,*,#463,.T.); +#661=ORIENTED_EDGE('',*,*,#472,.T.); +#662=ORIENTED_EDGE('',*,*,#507,.F.); +#663=ORIENTED_EDGE('',*,*,#508,.T.); +#664=ORIENTED_EDGE('',*,*,#509,.F.); +#665=ORIENTED_EDGE('',*,*,#508,.F.); +#666=ORIENTED_EDGE('',*,*,#510,.F.); +#667=ORIENTED_EDGE('',*,*,#511,.T.); +#668=ORIENTED_EDGE('',*,*,#512,.F.); +#669=ORIENTED_EDGE('',*,*,#511,.F.); +#670=ORIENTED_EDGE('',*,*,#513,.F.); +#671=ORIENTED_EDGE('',*,*,#514,.T.); +#672=ORIENTED_EDGE('',*,*,#515,.F.); +#673=ORIENTED_EDGE('',*,*,#514,.F.); +#674=ORIENTED_EDGE('',*,*,#516,.F.); +#675=ORIENTED_EDGE('',*,*,#517,.T.); +#676=ORIENTED_EDGE('',*,*,#518,.F.); +#677=ORIENTED_EDGE('',*,*,#517,.F.); +#678=ORIENTED_EDGE('',*,*,#519,.F.); +#679=ORIENTED_EDGE('',*,*,#520,.T.); +#680=ORIENTED_EDGE('',*,*,#521,.F.); +#681=ORIENTED_EDGE('',*,*,#520,.F.); +#682=ORIENTED_EDGE('',*,*,#522,.F.); +#683=ORIENTED_EDGE('',*,*,#523,.T.); +#684=ORIENTED_EDGE('',*,*,#524,.F.); +#685=ORIENTED_EDGE('',*,*,#523,.F.); +#686=ORIENTED_EDGE('',*,*,#525,.F.); +#687=ORIENTED_EDGE('',*,*,#526,.T.); +#688=ORIENTED_EDGE('',*,*,#527,.F.); +#689=ORIENTED_EDGE('',*,*,#526,.F.); +#690=ORIENTED_EDGE('',*,*,#528,.T.); +#691=ORIENTED_EDGE('',*,*,#499,.T.); +#692=ORIENTED_EDGE('',*,*,#529,.T.); +#693=ORIENTED_EDGE('',*,*,#530,.T.); +#694=ORIENTED_EDGE('',*,*,#530,.F.); +#695=ORIENTED_EDGE('',*,*,#531,.F.); +#696=ORIENTED_EDGE('',*,*,#532,.F.); +#697=ORIENTED_EDGE('',*,*,#533,.F.); +#698=ORIENTED_EDGE('',*,*,#534,.T.); +#699=ORIENTED_EDGE('',*,*,#535,.T.); +#700=ORIENTED_EDGE('',*,*,#536,.T.); +#701=ORIENTED_EDGE('',*,*,#503,.T.); +#702=ORIENTED_EDGE('',*,*,#535,.F.); +#703=ORIENTED_EDGE('',*,*,#537,.F.); +#704=ORIENTED_EDGE('',*,*,#538,.F.); +#705=ORIENTED_EDGE('',*,*,#539,.F.); +#706=ORIENTED_EDGE('',*,*,#540,.T.); +#707=ORIENTED_EDGE('',*,*,#532,.T.); +#708=ORIENTED_EDGE('',*,*,#541,.T.); +#709=ORIENTED_EDGE('',*,*,#542,.T.); +#710=ORIENTED_EDGE('',*,*,#542,.F.); +#711=ORIENTED_EDGE('',*,*,#543,.F.); +#712=ORIENTED_EDGE('',*,*,#544,.F.); +#713=ORIENTED_EDGE('',*,*,#545,.F.); +#714=ORIENTED_EDGE('',*,*,#507,.T.); +#715=ORIENTED_EDGE('',*,*,#510,.T.); +#716=ORIENTED_EDGE('',*,*,#513,.T.); +#717=ORIENTED_EDGE('',*,*,#516,.T.); +#718=ORIENTED_EDGE('',*,*,#519,.T.); +#719=ORIENTED_EDGE('',*,*,#522,.T.); +#720=ORIENTED_EDGE('',*,*,#525,.T.); +#721=ORIENTED_EDGE('',*,*,#546,.T.); +#722=ORIENTED_EDGE('',*,*,#544,.T.); +#723=ORIENTED_EDGE('',*,*,#547,.T.); +#724=ORIENTED_EDGE('',*,*,#538,.T.); +#725=ORIENTED_EDGE('',*,*,#548,.F.); +#726=ORIENTED_EDGE('',*,*,#549,.F.); +#727=ORIENTED_EDGE('',*,*,#550,.F.); +#728=ORIENTED_EDGE('',*,*,#505,.F.); +#729=ORIENTED_EDGE('',*,*,#549,.T.); +#730=ORIENTED_EDGE('',*,*,#551,.T.); +#731=ORIENTED_EDGE('',*,*,#552,.T.); +#732=ORIENTED_EDGE('',*,*,#553,.T.); +#733=ORIENTED_EDGE('',*,*,#554,.F.); +#734=ORIENTED_EDGE('',*,*,#497,.F.); +#735=ORIENTED_EDGE('',*,*,#555,.F.); +#736=ORIENTED_EDGE('',*,*,#556,.F.); +#737=ORIENTED_EDGE('',*,*,#556,.T.); +#738=ORIENTED_EDGE('',*,*,#557,.T.); +#739=ORIENTED_EDGE('',*,*,#558,.T.); +#740=ORIENTED_EDGE('',*,*,#559,.T.); +#741=ORIENTED_EDGE('',*,*,#560,.F.); +#742=ORIENTED_EDGE('',*,*,#561,.F.); +#743=ORIENTED_EDGE('',*,*,#562,.F.); +#744=ORIENTED_EDGE('',*,*,#552,.F.); +#745=ORIENTED_EDGE('',*,*,#561,.T.); +#746=ORIENTED_EDGE('',*,*,#563,.T.); +#747=ORIENTED_EDGE('',*,*,#564,.T.); +#748=ORIENTED_EDGE('',*,*,#565,.T.); +#749=ORIENTED_EDGE('',*,*,#509,.T.); +#750=ORIENTED_EDGE('',*,*,#512,.T.); +#751=ORIENTED_EDGE('',*,*,#515,.T.); +#752=ORIENTED_EDGE('',*,*,#518,.T.); +#753=ORIENTED_EDGE('',*,*,#521,.T.); +#754=ORIENTED_EDGE('',*,*,#524,.T.); +#755=ORIENTED_EDGE('',*,*,#527,.T.); +#756=ORIENTED_EDGE('',*,*,#566,.F.); +#757=ORIENTED_EDGE('',*,*,#558,.F.); +#758=ORIENTED_EDGE('',*,*,#567,.F.); +#759=ORIENTED_EDGE('',*,*,#564,.F.); +#760=ORIENTED_EDGE('',*,*,#548,.T.); +#761=ORIENTED_EDGE('',*,*,#568,.T.); +#762=ORIENTED_EDGE('',*,*,#528,.F.); +#763=ORIENTED_EDGE('',*,*,#569,.F.); +#764=ORIENTED_EDGE('',*,*,#550,.T.); +#765=ORIENTED_EDGE('',*,*,#570,.T.); +#766=ORIENTED_EDGE('',*,*,#529,.F.); +#767=ORIENTED_EDGE('',*,*,#571,.F.); +#768=ORIENTED_EDGE('',*,*,#553,.F.); +#769=ORIENTED_EDGE('',*,*,#572,.T.); +#770=ORIENTED_EDGE('',*,*,#531,.T.); +#771=ORIENTED_EDGE('',*,*,#570,.F.); +#772=ORIENTED_EDGE('',*,*,#551,.F.); +#773=ORIENTED_EDGE('',*,*,#569,.T.); +#774=ORIENTED_EDGE('',*,*,#533,.T.); +#775=ORIENTED_EDGE('',*,*,#573,.F.); +#776=ORIENTED_EDGE('',*,*,#486,.T.); +#777=ORIENTED_EDGE('',*,*,#500,.T.); +#778=ORIENTED_EDGE('',*,*,#568,.F.); +#779=ORIENTED_EDGE('',*,*,#504,.F.); +#780=ORIENTED_EDGE('',*,*,#488,.T.); +#781=ORIENTED_EDGE('',*,*,#506,.F.); +#782=ORIENTED_EDGE('',*,*,#571,.T.); +#783=ORIENTED_EDGE('',*,*,#498,.T.); +#784=ORIENTED_EDGE('',*,*,#554,.T.); +#785=ORIENTED_EDGE('',*,*,#574,.T.); +#786=ORIENTED_EDGE('',*,*,#534,.F.); +#787=ORIENTED_EDGE('',*,*,#494,.F.); +#788=ORIENTED_EDGE('',*,*,#555,.T.); +#789=ORIENTED_EDGE('',*,*,#502,.T.); +#790=ORIENTED_EDGE('',*,*,#536,.F.); +#791=ORIENTED_EDGE('',*,*,#575,.F.); +#792=ORIENTED_EDGE('',*,*,#559,.F.); +#793=ORIENTED_EDGE('',*,*,#576,.T.); +#794=ORIENTED_EDGE('',*,*,#537,.T.); +#795=ORIENTED_EDGE('',*,*,#574,.F.); +#796=ORIENTED_EDGE('',*,*,#557,.F.); +#797=ORIENTED_EDGE('',*,*,#575,.T.); +#798=ORIENTED_EDGE('',*,*,#539,.T.); +#799=ORIENTED_EDGE('',*,*,#577,.F.); +#800=ORIENTED_EDGE('',*,*,#560,.T.); +#801=ORIENTED_EDGE('',*,*,#573,.T.); +#802=ORIENTED_EDGE('',*,*,#540,.F.); +#803=ORIENTED_EDGE('',*,*,#578,.F.); +#804=ORIENTED_EDGE('',*,*,#562,.T.); +#805=ORIENTED_EDGE('',*,*,#579,.T.); +#806=ORIENTED_EDGE('',*,*,#541,.F.); +#807=ORIENTED_EDGE('',*,*,#572,.F.); +#808=ORIENTED_EDGE('',*,*,#565,.F.); +#809=ORIENTED_EDGE('',*,*,#580,.T.); +#810=ORIENTED_EDGE('',*,*,#543,.T.); +#811=ORIENTED_EDGE('',*,*,#579,.F.); +#812=ORIENTED_EDGE('',*,*,#563,.F.); +#813=ORIENTED_EDGE('',*,*,#578,.T.); +#814=ORIENTED_EDGE('',*,*,#545,.T.); +#815=ORIENTED_EDGE('',*,*,#581,.F.); +#816=ORIENTED_EDGE('',*,*,#566,.T.); +#817=ORIENTED_EDGE('',*,*,#581,.T.); +#818=ORIENTED_EDGE('',*,*,#546,.F.); +#819=ORIENTED_EDGE('',*,*,#576,.F.); +#820=ORIENTED_EDGE('',*,*,#567,.T.); +#821=ORIENTED_EDGE('',*,*,#577,.T.); +#822=ORIENTED_EDGE('',*,*,#547,.F.); +#823=ORIENTED_EDGE('',*,*,#580,.F.); +#824=CYLINDRICAL_SURFACE('',#914,2.65); +#825=CYLINDRICAL_SURFACE('',#917,2.65); +#826=CYLINDRICAL_SURFACE('',#920,2.65); +#827=CYLINDRICAL_SURFACE('',#923,2.65); +#828=CYLINDRICAL_SURFACE('',#926,8.50235261560071); +#829=CYLINDRICAL_SURFACE('',#930,8.50235261560071); +#830=CYLINDRICAL_SURFACE('',#933,8.50235261560071); +#831=CYLINDRICAL_SURFACE('',#936,8.50235261560071); +#832=CYLINDRICAL_SURFACE('',#946,1.6); +#833=CYLINDRICAL_SURFACE('',#949,1.6); +#834=CYLINDRICAL_SURFACE('',#952,1.6); +#835=CYLINDRICAL_SURFACE('',#955,1.6); +#836=CYLINDRICAL_SURFACE('',#958,1.6); +#837=CYLINDRICAL_SURFACE('',#961,1.6); +#838=CYLINDRICAL_SURFACE('',#964,21.5); +#839=CYLINDRICAL_SURFACE('',#967,0.1); +#840=CYLINDRICAL_SURFACE('',#971,0.1); +#841=CYLINDRICAL_SURFACE('',#975,2.6); +#842=CYLINDRICAL_SURFACE('',#979,2.6); +#843=CYLINDRICAL_SURFACE('',#982,2.6); +#844=CYLINDRICAL_SURFACE('',#986,2.6); +#845=CYLINDRICAL_SURFACE('',#990,0.1); +#846=CYLINDRICAL_SURFACE('',#994,0.1); +#847=ADVANCED_FACE('',(#67),#824,.F.); +#848=ADVANCED_FACE('',(#68),#825,.F.); +#849=ADVANCED_FACE('',(#69),#826,.F.); +#850=ADVANCED_FACE('',(#70),#827,.F.); +#851=ADVANCED_FACE('',(#71),#828,.T.); +#852=ADVANCED_FACE('',(#72),#37,.F.); +#853=ADVANCED_FACE('',(#73),#829,.T.); +#854=ADVANCED_FACE('',(#74),#830,.T.); +#855=ADVANCED_FACE('',(#75),#831,.T.); +#856=ADVANCED_FACE('',(#76),#38,.F.); +#857=ADVANCED_FACE('',(#77),#39,.F.); +#858=ADVANCED_FACE('',(#78,#15,#16),#40,.F.); +#859=ADVANCED_FACE('',(#79,#17,#18),#41,.T.); +#860=ADVANCED_FACE('',(#80),#42,.F.); +#861=ADVANCED_FACE('',(#81,#19,#20),#43,.T.); +#862=ADVANCED_FACE('',(#82,#21,#22),#44,.F.); +#863=ADVANCED_FACE('',(#83),#832,.F.); +#864=ADVANCED_FACE('',(#84),#833,.F.); +#865=ADVANCED_FACE('',(#85),#834,.F.); +#866=ADVANCED_FACE('',(#86),#835,.F.); +#867=ADVANCED_FACE('',(#87),#836,.F.); +#868=ADVANCED_FACE('',(#88),#837,.F.); +#869=ADVANCED_FACE('',(#89),#838,.F.); +#870=ADVANCED_FACE('',(#90),#839,.F.); +#871=ADVANCED_FACE('',(#91),#45,.T.); +#872=ADVANCED_FACE('',(#92),#840,.F.); +#873=ADVANCED_FACE('',(#93),#46,.T.); +#874=ADVANCED_FACE('',(#94),#841,.T.); +#875=ADVANCED_FACE('',(#95,#23,#24,#25,#26,#27,#28,#29),#47,.T.); +#876=ADVANCED_FACE('',(#96),#842,.T.); +#877=ADVANCED_FACE('',(#97),#843,.T.); +#878=ADVANCED_FACE('',(#98),#48,.F.); +#879=ADVANCED_FACE('',(#99),#844,.T.); +#880=ADVANCED_FACE('',(#100),#49,.F.); +#881=ADVANCED_FACE('',(#101),#845,.F.); +#882=ADVANCED_FACE('',(#102,#30,#31,#32,#33,#34,#35,#36),#50,.F.); +#883=ADVANCED_FACE('',(#103),#846,.F.); +#884=ADVANCED_FACE('',(#104),#51,.F.); +#885=ADVANCED_FACE('',(#105),#52,.F.); +#886=ADVANCED_FACE('',(#106),#53,.F.); +#887=ADVANCED_FACE('',(#107),#54,.F.); +#888=ADVANCED_FACE('',(#108),#55,.F.); +#889=ADVANCED_FACE('',(#109),#56,.F.); +#890=ADVANCED_FACE('',(#110),#57,.F.); +#891=ADVANCED_FACE('',(#111),#58,.F.); +#892=ADVANCED_FACE('',(#112),#59,.F.); +#893=ADVANCED_FACE('',(#113),#60,.F.); +#894=ADVANCED_FACE('',(#114),#61,.F.); +#895=ADVANCED_FACE('',(#115),#62,.F.); +#896=ADVANCED_FACE('',(#116),#63,.F.); +#897=ADVANCED_FACE('',(#117),#64,.F.); +#898=ADVANCED_FACE('',(#118),#65,.F.); +#899=ADVANCED_FACE('',(#119),#66,.F.); +#900=CLOSED_SHELL('',(#847,#848,#849,#850,#851,#852,#853,#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)); +#901=DERIVED_UNIT_ELEMENT(#903,1.); +#902=DERIVED_UNIT_ELEMENT(#1538,-3.); +#903=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT(.KILO.,.GRAM.) +); +#904=DERIVED_UNIT((#901,#902)); +#905=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(2680.),#904); +#906=PROPERTY_DEFINITION_REPRESENTATION(#911,#908); +#907=PROPERTY_DEFINITION_REPRESENTATION(#912,#909); +#908=REPRESENTATION('material name',(#910),#1535); +#909=REPRESENTATION('density',(#905),#1535); +#910=DESCRIPTIVE_REPRESENTATION_ITEM('Aluminum 5052','Aluminum 5052'); +#911=PROPERTY_DEFINITION('material property','material name',#1545); +#912=PROPERTY_DEFINITION('material property','density of part',#1545); +#913=AXIS2_PLACEMENT_3D('',#1288,#1013,#1014); +#914=AXIS2_PLACEMENT_3D('',#1289,#1015,#1016); +#915=AXIS2_PLACEMENT_3D('',#1291,#1017,#1018); +#916=AXIS2_PLACEMENT_3D('',#1294,#1020,#1021); +#917=AXIS2_PLACEMENT_3D('',#1295,#1022,#1023); +#918=AXIS2_PLACEMENT_3D('',#1297,#1024,#1025); +#919=AXIS2_PLACEMENT_3D('',#1300,#1027,#1028); +#920=AXIS2_PLACEMENT_3D('',#1301,#1029,#1030); +#921=AXIS2_PLACEMENT_3D('',#1303,#1031,#1032); +#922=AXIS2_PLACEMENT_3D('',#1306,#1034,#1035); +#923=AXIS2_PLACEMENT_3D('',#1307,#1036,#1037); +#924=AXIS2_PLACEMENT_3D('',#1309,#1038,#1039); +#925=AXIS2_PLACEMENT_3D('',#1312,#1041,#1042); +#926=AXIS2_PLACEMENT_3D('',#1313,#1043,#1044); +#927=AXIS2_PLACEMENT_3D('',#1316,#1045,#1046); +#928=AXIS2_PLACEMENT_3D('',#1320,#1048,#1049); +#929=AXIS2_PLACEMENT_3D('',#1322,#1051,#1052); +#930=AXIS2_PLACEMENT_3D('',#1328,#1056,#1057); +#931=AXIS2_PLACEMENT_3D('',#1330,#1058,#1059); +#932=AXIS2_PLACEMENT_3D('',#1332,#1060,#1061); +#933=AXIS2_PLACEMENT_3D('',#1334,#1063,#1064); +#934=AXIS2_PLACEMENT_3D('',#1337,#1065,#1066); +#935=AXIS2_PLACEMENT_3D('',#1341,#1068,#1069); +#936=AXIS2_PLACEMENT_3D('',#1343,#1071,#1072); +#937=AXIS2_PLACEMENT_3D('',#1346,#1073,#1074); +#938=AXIS2_PLACEMENT_3D('',#1350,#1076,#1077); +#939=AXIS2_PLACEMENT_3D('',#1352,#1079,#1080); +#940=AXIS2_PLACEMENT_3D('',#1355,#1083,#1084); +#941=AXIS2_PLACEMENT_3D('',#1361,#1088,#1089); +#942=AXIS2_PLACEMENT_3D('',#1365,#1092,#1093); +#943=AXIS2_PLACEMENT_3D('',#1371,#1097,#1098); +#944=AXIS2_PLACEMENT_3D('',#1375,#1101,#1102); +#945=AXIS2_PLACEMENT_3D('',#1377,#1104,#1105); +#946=AXIS2_PLACEMENT_3D('',#1383,#1109,#1110); +#947=AXIS2_PLACEMENT_3D('',#1385,#1111,#1112); +#948=AXIS2_PLACEMENT_3D('',#1388,#1114,#1115); +#949=AXIS2_PLACEMENT_3D('',#1389,#1116,#1117); +#950=AXIS2_PLACEMENT_3D('',#1391,#1118,#1119); +#951=AXIS2_PLACEMENT_3D('',#1394,#1121,#1122); +#952=AXIS2_PLACEMENT_3D('',#1395,#1123,#1124); +#953=AXIS2_PLACEMENT_3D('',#1397,#1125,#1126); +#954=AXIS2_PLACEMENT_3D('',#1400,#1128,#1129); +#955=AXIS2_PLACEMENT_3D('',#1401,#1130,#1131); +#956=AXIS2_PLACEMENT_3D('',#1403,#1132,#1133); +#957=AXIS2_PLACEMENT_3D('',#1406,#1135,#1136); +#958=AXIS2_PLACEMENT_3D('',#1407,#1137,#1138); +#959=AXIS2_PLACEMENT_3D('',#1409,#1139,#1140); +#960=AXIS2_PLACEMENT_3D('',#1412,#1142,#1143); +#961=AXIS2_PLACEMENT_3D('',#1413,#1144,#1145); +#962=AXIS2_PLACEMENT_3D('',#1415,#1146,#1147); +#963=AXIS2_PLACEMENT_3D('',#1418,#1149,#1150); +#964=AXIS2_PLACEMENT_3D('',#1419,#1151,#1152); +#965=AXIS2_PLACEMENT_3D('',#1421,#1153,#1154); +#966=AXIS2_PLACEMENT_3D('',#1424,#1156,#1157); +#967=AXIS2_PLACEMENT_3D('',#1425,#1158,#1159); +#968=AXIS2_PLACEMENT_3D('',#1427,#1160,#1161); +#969=AXIS2_PLACEMENT_3D('',#1429,#1162,#1163); +#970=AXIS2_PLACEMENT_3D('',#1431,#1165,#1166); +#971=AXIS2_PLACEMENT_3D('',#1437,#1170,#1171); +#972=AXIS2_PLACEMENT_3D('',#1439,#1172,#1173); +#973=AXIS2_PLACEMENT_3D('',#1442,#1175,#1176); +#974=AXIS2_PLACEMENT_3D('',#1443,#1177,#1178); +#975=AXIS2_PLACEMENT_3D('',#1449,#1182,#1183); +#976=AXIS2_PLACEMENT_3D('',#1451,#1184,#1185); +#977=AXIS2_PLACEMENT_3D('',#1453,#1186,#1187); +#978=AXIS2_PLACEMENT_3D('',#1455,#1189,#1190); +#979=AXIS2_PLACEMENT_3D('',#1461,#1194,#1195); +#980=AXIS2_PLACEMENT_3D('',#1462,#1196,#1197); +#981=AXIS2_PLACEMENT_3D('',#1463,#1198,#1199); +#982=AXIS2_PLACEMENT_3D('',#1464,#1200,#1201); +#983=AXIS2_PLACEMENT_3D('',#1466,#1202,#1203); +#984=AXIS2_PLACEMENT_3D('',#1469,#1205,#1206); +#985=AXIS2_PLACEMENT_3D('',#1470,#1207,#1208); +#986=AXIS2_PLACEMENT_3D('',#1476,#1212,#1213); +#987=AXIS2_PLACEMENT_3D('',#1478,#1214,#1215); +#988=AXIS2_PLACEMENT_3D('',#1480,#1216,#1217); +#989=AXIS2_PLACEMENT_3D('',#1482,#1219,#1220); +#990=AXIS2_PLACEMENT_3D('',#1488,#1224,#1225); +#991=AXIS2_PLACEMENT_3D('',#1490,#1226,#1227); +#992=AXIS2_PLACEMENT_3D('',#1493,#1229,#1230); +#993=AXIS2_PLACEMENT_3D('',#1494,#1231,#1232); +#994=AXIS2_PLACEMENT_3D('',#1500,#1236,#1237); +#995=AXIS2_PLACEMENT_3D('',#1501,#1238,#1239); +#996=AXIS2_PLACEMENT_3D('',#1502,#1240,#1241); +#997=AXIS2_PLACEMENT_3D('',#1503,#1242,#1243); +#998=AXIS2_PLACEMENT_3D('',#1506,#1246,#1247); +#999=AXIS2_PLACEMENT_3D('',#1509,#1250,#1251); +#1000=AXIS2_PLACEMENT_3D('',#1511,#1253,#1254); +#1001=AXIS2_PLACEMENT_3D('',#1513,#1256,#1257); +#1002=AXIS2_PLACEMENT_3D('',#1514,#1258,#1259); +#1003=AXIS2_PLACEMENT_3D('',#1515,#1260,#1261); +#1004=AXIS2_PLACEMENT_3D('',#1517,#1263,#1264); +#1005=AXIS2_PLACEMENT_3D('',#1519,#1266,#1267); +#1006=AXIS2_PLACEMENT_3D('',#1521,#1269,#1270); +#1007=AXIS2_PLACEMENT_3D('',#1523,#1272,#1273); +#1008=AXIS2_PLACEMENT_3D('',#1525,#1275,#1276); +#1009=AXIS2_PLACEMENT_3D('',#1527,#1278,#1279); +#1010=AXIS2_PLACEMENT_3D('',#1529,#1281,#1282); +#1011=AXIS2_PLACEMENT_3D('',#1531,#1284,#1285); +#1012=AXIS2_PLACEMENT_3D('',#1532,#1286,#1287); +#1013=DIRECTION('axis',(0.,0.,1.)); +#1014=DIRECTION('refdir',(1.,0.,0.)); +#1015=DIRECTION('center_axis',(-6.17284001691587E-14,-1.,0.)); +#1016=DIRECTION('ref_axis',(0.,0.,1.)); +#1017=DIRECTION('center_axis',(6.17284001691587E-14,-1.,0.)); +#1018=DIRECTION('ref_axis',(0.,0.,1.)); +#1019=DIRECTION('',(-6.17284001691587E-14,-1.,0.)); +#1020=DIRECTION('center_axis',(-6.17284001691587E-14,1.,0.)); +#1021=DIRECTION('ref_axis',(0.,0.,1.)); +#1022=DIRECTION('center_axis',(-6.17284001691587E-14,-1.,0.)); +#1023=DIRECTION('ref_axis',(0.,0.,1.)); +#1024=DIRECTION('center_axis',(-6.17284001691587E-14,-1.,0.)); +#1025=DIRECTION('ref_axis',(0.,0.,1.)); +#1026=DIRECTION('',(-6.17284001691587E-14,-1.,0.)); +#1027=DIRECTION('center_axis',(6.17284001691587E-14,1.,0.)); +#1028=DIRECTION('ref_axis',(0.,0.,1.)); +#1029=DIRECTION('center_axis',(-6.17284001691587E-14,-1.,0.)); +#1030=DIRECTION('ref_axis',(0.,0.,1.)); +#1031=DIRECTION('center_axis',(-6.17284001691587E-14,-1.,0.)); +#1032=DIRECTION('ref_axis',(0.,0.,1.)); +#1033=DIRECTION('',(-6.17284001691587E-14,-1.,0.)); +#1034=DIRECTION('center_axis',(6.17284001691587E-14,1.,0.)); +#1035=DIRECTION('ref_axis',(0.,0.,1.)); +#1036=DIRECTION('center_axis',(-6.17284001691587E-14,-1.,0.)); +#1037=DIRECTION('ref_axis',(0.,0.,1.)); +#1038=DIRECTION('center_axis',(6.17284001691587E-14,-1.,0.)); +#1039=DIRECTION('ref_axis',(0.,0.,1.)); +#1040=DIRECTION('',(-6.17284001691587E-14,-1.,0.)); +#1041=DIRECTION('center_axis',(-6.17284001691587E-14,1.,0.)); +#1042=DIRECTION('ref_axis',(0.,0.,1.)); +#1043=DIRECTION('center_axis',(-6.21724893790088E-14,-1.,0.)); +#1044=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1045=DIRECTION('center_axis',(-6.17284001691587E-14,-1.,0.)); +#1046=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1047=DIRECTION('',(-6.21724893790088E-14,-1.,0.)); +#1048=DIRECTION('center_axis',(6.17284001691587E-14,1.,0.)); +#1049=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1050=DIRECTION('',(-6.21724893790088E-14,-1.,0.)); +#1051=DIRECTION('center_axis',(1.,-6.21724893790088E-14,0.)); +#1052=DIRECTION('ref_axis',(0.,0.,1.)); +#1053=DIRECTION('',(0.,0.,-1.)); +#1054=DIRECTION('',(0.,0.,1.)); +#1055=DIRECTION('',(-6.21724893790088E-14,-1.,0.)); +#1056=DIRECTION('center_axis',(-6.21724893790088E-14,-1.,0.)); +#1057=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1058=DIRECTION('center_axis',(-6.17284001691587E-14,-1.,0.)); +#1059=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1060=DIRECTION('center_axis',(6.17284001691587E-14,1.,0.)); +#1061=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1062=DIRECTION('',(6.21724893790088E-14,1.,0.)); +#1063=DIRECTION('center_axis',(-6.21724893790088E-14,-1.,0.)); +#1064=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1065=DIRECTION('center_axis',(6.17284001691587E-14,-1.,0.)); +#1066=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1067=DIRECTION('',(-6.21724893790088E-14,-1.,0.)); +#1068=DIRECTION('center_axis',(-6.17284001691587E-14,1.,0.)); +#1069=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1070=DIRECTION('',(6.21724893790088E-14,1.,0.)); +#1071=DIRECTION('center_axis',(-6.21724893790088E-14,-1.,0.)); +#1072=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1073=DIRECTION('center_axis',(6.17284001691587E-14,-1.,0.)); +#1074=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1075=DIRECTION('',(-6.21724893790088E-14,-1.,0.)); +#1076=DIRECTION('center_axis',(-6.17284001691587E-14,1.,0.)); +#1077=DIRECTION('ref_axis',(1.,-6.21724893790088E-14,0.)); +#1078=DIRECTION('',(-6.21724893790088E-14,-1.,0.)); +#1079=DIRECTION('center_axis',(-1.,6.21724893790088E-14,0.)); +#1080=DIRECTION('ref_axis',(0.,0.,-1.)); +#1081=DIRECTION('',(0.,0.,1.)); +#1082=DIRECTION('',(0.,0.,-1.)); +#1083=DIRECTION('center_axis',(0.,0.,-1.)); +#1084=DIRECTION('ref_axis',(-1.,0.,0.)); +#1085=DIRECTION('',(-1.,6.17284001691587E-14,0.)); +#1086=DIRECTION('',(6.16088376895837E-14,1.,0.)); +#1087=DIRECTION('',(-1.,6.17284001691587E-14,0.)); +#1088=DIRECTION('center_axis',(6.17284001691587E-14,1.,0.)); +#1089=DIRECTION('ref_axis',(-1.,6.17284001691587E-14,0.)); +#1090=DIRECTION('',(1.,-6.17284001691587E-14,0.)); +#1091=DIRECTION('',(0.,0.,1.)); +#1092=DIRECTION('center_axis',(-6.17284001691587E-14,1.,0.)); +#1093=DIRECTION('ref_axis',(-1.,-6.17284001691587E-14,0.)); +#1094=DIRECTION('',(1.,6.17284001691587E-14,0.)); +#1095=DIRECTION('',(0.,0.,-1.)); +#1096=DIRECTION('',(-1.,-6.17284001691587E-14,0.)); +#1097=DIRECTION('center_axis',(0.,0.,1.)); +#1098=DIRECTION('ref_axis',(1.,0.,0.)); +#1099=DIRECTION('',(1.,-6.17284001691587E-14,0.)); +#1100=DIRECTION('',(6.16088376895837E-14,1.,0.)); +#1101=DIRECTION('center_axis',(6.17284001691587E-14,1.,0.)); +#1102=DIRECTION('ref_axis',(-1.,6.17284001691587E-14,0.)); +#1103=DIRECTION('',(0.,0.,1.)); +#1104=DIRECTION('center_axis',(-6.17284001691587E-14,1.,0.)); +#1105=DIRECTION('ref_axis',(-1.,-6.17284001691587E-14,0.)); +#1106=DIRECTION('',(-1.,-6.17284001691587E-14,0.)); +#1107=DIRECTION('',(0.,0.,-1.)); +#1108=DIRECTION('',(1.,6.17284001691587E-14,0.)); +#1109=DIRECTION('center_axis',(0.,-1.,0.)); +#1110=DIRECTION('ref_axis',(0.,0.,1.)); +#1111=DIRECTION('center_axis',(1.03401731621482E-11,-1.,0.)); +#1112=DIRECTION('ref_axis',(0.,0.,1.)); +#1113=DIRECTION('',(0.,-1.,0.)); +#1114=DIRECTION('center_axis',(-1.03401731621482E-11,1.,0.)); +#1115=DIRECTION('ref_axis',(0.,0.,1.)); +#1116=DIRECTION('center_axis',(0.,-1.,0.)); +#1117=DIRECTION('ref_axis',(0.,0.,1.)); +#1118=DIRECTION('center_axis',(1.03401731621482E-11,-1.,0.)); +#1119=DIRECTION('ref_axis',(0.,0.,1.)); +#1120=DIRECTION('',(0.,-1.,0.)); +#1121=DIRECTION('center_axis',(-1.03401731621482E-11,1.,0.)); +#1122=DIRECTION('ref_axis',(0.,0.,1.)); +#1123=DIRECTION('center_axis',(0.,-1.,0.)); +#1124=DIRECTION('ref_axis',(0.,0.,1.)); +#1125=DIRECTION('center_axis',(1.03401731621482E-11,-1.,0.)); +#1126=DIRECTION('ref_axis',(0.,0.,1.)); +#1127=DIRECTION('',(0.,-1.,0.)); +#1128=DIRECTION('center_axis',(-1.03401731621482E-11,1.,0.)); +#1129=DIRECTION('ref_axis',(0.,0.,1.)); +#1130=DIRECTION('center_axis',(0.,-1.,0.)); +#1131=DIRECTION('ref_axis',(0.,0.,1.)); +#1132=DIRECTION('center_axis',(1.03401731621482E-11,-1.,0.)); +#1133=DIRECTION('ref_axis',(0.,0.,1.)); +#1134=DIRECTION('',(0.,-1.,0.)); +#1135=DIRECTION('center_axis',(-1.03401731621482E-11,1.,0.)); +#1136=DIRECTION('ref_axis',(0.,0.,1.)); +#1137=DIRECTION('center_axis',(0.,-1.,0.)); +#1138=DIRECTION('ref_axis',(0.,0.,1.)); +#1139=DIRECTION('center_axis',(1.03401731621482E-11,-1.,0.)); +#1140=DIRECTION('ref_axis',(0.,0.,1.)); +#1141=DIRECTION('',(0.,-1.,0.)); +#1142=DIRECTION('center_axis',(-1.03401731621482E-11,1.,0.)); +#1143=DIRECTION('ref_axis',(0.,0.,1.)); +#1144=DIRECTION('center_axis',(0.,-1.,0.)); +#1145=DIRECTION('ref_axis',(0.,0.,1.)); +#1146=DIRECTION('center_axis',(1.03401731621482E-11,-1.,0.)); +#1147=DIRECTION('ref_axis',(0.,0.,1.)); +#1148=DIRECTION('',(0.,-1.,0.)); +#1149=DIRECTION('center_axis',(-1.03401731621482E-11,1.,0.)); +#1150=DIRECTION('ref_axis',(0.,0.,1.)); +#1151=DIRECTION('center_axis',(0.,-1.,0.)); +#1152=DIRECTION('ref_axis',(-1.,0.,0.)); +#1153=DIRECTION('center_axis',(1.03401731621482E-11,-1.,0.)); +#1154=DIRECTION('ref_axis',(-1.,0.,0.)); +#1155=DIRECTION('',(0.,-1.,0.)); +#1156=DIRECTION('center_axis',(-1.03401731621482E-11,1.,0.)); +#1157=DIRECTION('ref_axis',(-1.,0.,0.)); +#1158=DIRECTION('center_axis',(0.,0.,1.)); +#1159=DIRECTION('ref_axis',(-0.707106781186697,-0.707106781186398,0.)); +#1160=DIRECTION('center_axis',(0.,0.,1.)); +#1161=DIRECTION('ref_axis',(-0.707106781186699,-0.707106781186396,0.)); +#1162=DIRECTION('center_axis',(0.,0.,-1.)); +#1163=DIRECTION('ref_axis',(-0.707106781186699,-0.707106781186396,0.)); +#1164=DIRECTION('',(0.,0.,1.)); +#1165=DIRECTION('center_axis',(1.,-4.88133126005055E-13,0.)); +#1166=DIRECTION('ref_axis',(4.88133126005055E-13,1.,0.)); +#1167=DIRECTION('',(-4.88133126005055E-13,-1.,0.)); +#1168=DIRECTION('',(0.,0.,-1.)); +#1169=DIRECTION('',(4.88133126005055E-13,1.,0.)); +#1170=DIRECTION('center_axis',(0.,0.,1.)); +#1171=DIRECTION('ref_axis',(0.707106781186697,-0.707106781186398,0.)); +#1172=DIRECTION('center_axis',(0.,0.,1.)); +#1173=DIRECTION('ref_axis',(0.707106781186699,-0.707106781186396,0.)); +#1174=DIRECTION('',(0.,0.,-1.)); +#1175=DIRECTION('center_axis',(0.,0.,-1.)); +#1176=DIRECTION('ref_axis',(0.707106781186699,-0.707106781186396,0.)); +#1177=DIRECTION('center_axis',(-1.,-4.88133126005055E-13,0.)); +#1178=DIRECTION('ref_axis',(4.88133126005055E-13,-1.,0.)); +#1179=DIRECTION('',(4.88133126005055E-13,-1.,0.)); +#1180=DIRECTION('',(0.,0.,1.)); +#1181=DIRECTION('',(-4.88133126005055E-13,1.,0.)); +#1182=DIRECTION('center_axis',(0.,0.,1.)); +#1183=DIRECTION('ref_axis',(0.70710678118303,0.707106781190065,0.)); +#1184=DIRECTION('center_axis',(0.,0.,-1.)); +#1185=DIRECTION('ref_axis',(0.707106781183061,0.707106781190034,0.)); +#1186=DIRECTION('center_axis',(0.,0.,1.)); +#1187=DIRECTION('ref_axis',(0.707106781183061,0.707106781190034,0.)); +#1188=DIRECTION('',(0.,0.,1.)); +#1189=DIRECTION('center_axis',(-1.03401731621482E-11,1.,0.)); +#1190=DIRECTION('ref_axis',(-1.,-1.03401731621482E-11,0.)); +#1191=DIRECTION('',(1.,-1.03348440916299E-11,0.)); +#1192=DIRECTION('',(0.,0.,-1.)); +#1193=DIRECTION('',(-1.,-1.03401731621482E-11,0.)); +#1194=DIRECTION('center_axis',(0.,0.,1.)); +#1195=DIRECTION('ref_axis',(-0.70710678119041,0.707106781182685,0.)); +#1196=DIRECTION('center_axis',(0.,0.,-1.)); +#1197=DIRECTION('ref_axis',(-0.707106781190389,0.707106781182706,0.)); +#1198=DIRECTION('center_axis',(0.,0.,1.)); +#1199=DIRECTION('ref_axis',(-0.707106781190389,0.707106781182706,0.)); +#1200=DIRECTION('center_axis',(0.,0.,1.)); +#1201=DIRECTION('ref_axis',(-0.707106781186697,-0.707106781186398,0.)); +#1202=DIRECTION('center_axis',(0.,0.,1.)); +#1203=DIRECTION('ref_axis',(-0.707106781186699,-0.707106781186396,0.)); +#1204=DIRECTION('',(0.,0.,1.)); +#1205=DIRECTION('center_axis',(0.,0.,-1.)); +#1206=DIRECTION('ref_axis',(-0.707106781186699,-0.707106781186396,0.)); +#1207=DIRECTION('center_axis',(1.,-4.88133126005055E-13,0.)); +#1208=DIRECTION('ref_axis',(4.88133126005055E-13,1.,0.)); +#1209=DIRECTION('',(4.88133126005055E-13,1.,0.)); +#1210=DIRECTION('',(0.,0.,-1.)); +#1211=DIRECTION('',(-4.88133126005055E-13,-1.,0.)); +#1212=DIRECTION('center_axis',(0.,0.,1.)); +#1213=DIRECTION('ref_axis',(0.707106781186697,-0.707106781186398,0.)); +#1214=DIRECTION('center_axis',(0.,0.,1.)); +#1215=DIRECTION('ref_axis',(0.707106781186699,-0.707106781186396,0.)); +#1216=DIRECTION('center_axis',(0.,0.,-1.)); +#1217=DIRECTION('ref_axis',(0.707106781186699,-0.707106781186396,0.)); +#1218=DIRECTION('',(0.,0.,-1.)); +#1219=DIRECTION('center_axis',(-1.,-4.88133126005055E-13,0.)); +#1220=DIRECTION('ref_axis',(4.88133126005055E-13,-1.,0.)); +#1221=DIRECTION('',(-4.88133126005055E-13,1.,0.)); +#1222=DIRECTION('',(0.,0.,1.)); +#1223=DIRECTION('',(4.88133126005055E-13,-1.,0.)); +#1224=DIRECTION('center_axis',(0.,0.,1.)); +#1225=DIRECTION('ref_axis',(0.70710678118303,0.707106781190065,0.)); +#1226=DIRECTION('center_axis',(0.,0.,-1.)); +#1227=DIRECTION('ref_axis',(0.707106781183061,0.707106781190034,0.)); +#1228=DIRECTION('',(0.,0.,1.)); +#1229=DIRECTION('center_axis',(0.,0.,1.)); +#1230=DIRECTION('ref_axis',(0.707106781183061,0.707106781190034,0.)); +#1231=DIRECTION('center_axis',(-1.03401731621482E-11,1.,0.)); +#1232=DIRECTION('ref_axis',(-1.,-1.03401731621482E-11,0.)); +#1233=DIRECTION('',(-1.,-1.03401731621482E-11,0.)); +#1234=DIRECTION('',(0.,0.,-1.)); +#1235=DIRECTION('',(1.,-1.03348440916299E-11,0.)); +#1236=DIRECTION('center_axis',(0.,0.,1.)); +#1237=DIRECTION('ref_axis',(-0.70710678119041,0.707106781182685,0.)); +#1238=DIRECTION('center_axis',(0.,0.,-1.)); +#1239=DIRECTION('ref_axis',(-0.707106781190389,0.707106781182706,0.)); +#1240=DIRECTION('center_axis',(0.,0.,1.)); +#1241=DIRECTION('ref_axis',(-0.707106781190389,0.707106781182706,0.)); +#1242=DIRECTION('center_axis',(0.,0.,-1.)); +#1243=DIRECTION('ref_axis',(-1.,0.,0.)); +#1244=DIRECTION('',(-6.16088376895837E-14,1.,0.)); +#1245=DIRECTION('',(1.,-4.88315628420062E-13,0.)); +#1246=DIRECTION('center_axis',(0.,0.,1.)); +#1247=DIRECTION('ref_axis',(1.,0.,0.)); +#1248=DIRECTION('',(1.,-4.88315628420062E-13,0.)); +#1249=DIRECTION('',(-6.16088376895837E-14,1.,0.)); +#1250=DIRECTION('center_axis',(0.,0.,1.)); +#1251=DIRECTION('ref_axis',(1.,0.,0.)); +#1252=DIRECTION('',(1.,-4.88315628420078E-13,0.)); +#1253=DIRECTION('center_axis',(0.,0.,-1.)); +#1254=DIRECTION('ref_axis',(-1.,0.,0.)); +#1255=DIRECTION('',(1.,-4.88315628420078E-13,0.)); +#1256=DIRECTION('center_axis',(0.,0.,-1.)); +#1257=DIRECTION('ref_axis',(-1.,0.,0.)); +#1258=DIRECTION('center_axis',(0.,0.,1.)); +#1259=DIRECTION('ref_axis',(1.,0.,0.)); +#1260=DIRECTION('center_axis',(0.,0.,-1.)); +#1261=DIRECTION('ref_axis',(-1.,0.,0.)); +#1262=DIRECTION('',(-1.,-4.88315628420062E-13,0.)); +#1263=DIRECTION('center_axis',(0.,0.,1.)); +#1264=DIRECTION('ref_axis',(1.,0.,0.)); +#1265=DIRECTION('',(-1.,-4.88315628420062E-13,0.)); +#1266=DIRECTION('center_axis',(0.,0.,-1.)); +#1267=DIRECTION('ref_axis',(-1.,0.,0.)); +#1268=DIRECTION('',(-1.,-4.88315628420067E-13,0.)); +#1269=DIRECTION('center_axis',(0.,0.,1.)); +#1270=DIRECTION('ref_axis',(1.,0.,0.)); +#1271=DIRECTION('',(-1.,-4.88315628420067E-13,0.)); +#1272=DIRECTION('center_axis',(0.,0.,-1.)); +#1273=DIRECTION('ref_axis',(-1.,0.,0.)); +#1274=DIRECTION('',(-1.03437258758274E-11,1.,0.)); +#1275=DIRECTION('center_axis',(0.,0.,1.)); +#1276=DIRECTION('ref_axis',(1.,0.,0.)); +#1277=DIRECTION('',(-1.03437259088711E-11,1.,0.)); +#1278=DIRECTION('center_axis',(0.,0.,1.)); +#1279=DIRECTION('ref_axis',(1.,0.,0.)); +#1280=DIRECTION('',(-1.03437258427669E-11,1.,0.)); +#1281=DIRECTION('center_axis',(0.,0.,-1.)); +#1282=DIRECTION('ref_axis',(-1.,0.,0.)); +#1283=DIRECTION('',(-1.03437258758276E-11,1.,0.)); +#1284=DIRECTION('center_axis',(0.,0.,-1.)); +#1285=DIRECTION('ref_axis',(-1.,0.,0.)); +#1286=DIRECTION('center_axis',(0.,0.,1.)); +#1287=DIRECTION('ref_axis',(1.,0.,0.)); +#1288=CARTESIAN_POINT('',(0.,0.,0.)); +#1289=CARTESIAN_POINT('Origin',(49.9999999999981,-30.8749999999776,-20.)); +#1290=CARTESIAN_POINT('',(49.9999999999985,-24.8749999999685,-22.65)); +#1291=CARTESIAN_POINT('Origin',(49.9999999999985,-24.8749999999688,-20.)); +#1292=CARTESIAN_POINT('',(49.9999999999983,-27.3749999999688,-22.65)); +#1293=CARTESIAN_POINT('',(49.9999999999981,-30.8749999999776,-22.65)); +#1294=CARTESIAN_POINT('Origin',(49.9999999999983,-27.3749999999688,-20.)); +#1295=CARTESIAN_POINT('Origin',(-50.0000000000019,-30.8749999999714,20.)); +#1296=CARTESIAN_POINT('',(-50.0000000000015,-24.8749999999714,17.35)); +#1297=CARTESIAN_POINT('Origin',(-50.0000000000015,-24.8749999999714,20.)); +#1298=CARTESIAN_POINT('',(-50.0000000000017,-27.3749999999714,17.35)); +#1299=CARTESIAN_POINT('',(-50.0000000000019,-30.8749999999714,17.35)); +#1300=CARTESIAN_POINT('Origin',(-50.0000000000017,-27.3749999999714,20.)); +#1301=CARTESIAN_POINT('Origin',(-50.0000000000019,-30.8749999999714,-20.)); +#1302=CARTESIAN_POINT('',(-50.0000000000015,-24.8749999999714,-22.65)); +#1303=CARTESIAN_POINT('Origin',(-50.0000000000015,-24.8749999999714,-20.)); +#1304=CARTESIAN_POINT('',(-50.0000000000017,-27.3749999999714,-22.65)); +#1305=CARTESIAN_POINT('',(-50.0000000000019,-30.8749999999714,-22.65)); +#1306=CARTESIAN_POINT('Origin',(-50.0000000000017,-27.3749999999714,-20.)); +#1307=CARTESIAN_POINT('Origin',(49.9999999999981,-30.8749999999776,20.)); +#1308=CARTESIAN_POINT('',(49.9999999999985,-24.8749999999685,17.35)); +#1309=CARTESIAN_POINT('Origin',(49.9999999999985,-24.8749999999688,20.)); +#1310=CARTESIAN_POINT('',(49.9999999999983,-27.3749999999688,17.35)); +#1311=CARTESIAN_POINT('',(49.9999999999981,-30.8749999999776,17.35)); +#1312=CARTESIAN_POINT('Origin',(49.9999999999983,-27.3749999999688,20.)); +#1313=CARTESIAN_POINT('Origin',(-50.0000000000015,-24.8749999999714,20.)); +#1314=CARTESIAN_POINT('',(-50.2000000000322,-27.3749999999714,28.5)); +#1315=CARTESIAN_POINT('',(-58.5023526156029,-27.3749999999709,20.)); +#1316=CARTESIAN_POINT('Origin',(-50.0000000000017,-27.3749999999714,20.)); +#1317=CARTESIAN_POINT('',(-50.200000000032,-24.8749999999714,28.5)); +#1318=CARTESIAN_POINT('',(-50.2000000000321,-24.8749999999714,28.5)); +#1319=CARTESIAN_POINT('',(-58.5023526156028,-24.8749999999709,20.)); +#1320=CARTESIAN_POINT('Origin',(-50.0000000000015,-24.8749999999714,20.)); +#1321=CARTESIAN_POINT('',(-58.5023526156028,-24.8749999999709,20.)); +#1322=CARTESIAN_POINT('Origin',(-58.5023526156028,-24.8749999999709,-20.)); +#1323=CARTESIAN_POINT('',(-58.5023526156029,-27.3749999999709,-20.)); +#1324=CARTESIAN_POINT('',(-58.5023526156029,-27.3749999999709,-10.)); +#1325=CARTESIAN_POINT('',(-58.5023526156028,-24.8749999999709,-20.)); +#1326=CARTESIAN_POINT('',(-58.5023526156028,-24.8749999999709,-10.)); +#1327=CARTESIAN_POINT('',(-58.5023526156028,-24.8749999999709,-20.)); +#1328=CARTESIAN_POINT('Origin',(-50.0000000000015,-24.8749999999714,-20.)); +#1329=CARTESIAN_POINT('',(-50.2000000000322,-27.3749999999714,-28.5)); +#1330=CARTESIAN_POINT('Origin',(-50.0000000000017,-27.3749999999714,-20.)); +#1331=CARTESIAN_POINT('',(-50.200000000032,-24.8749999999714,-28.5)); +#1332=CARTESIAN_POINT('Origin',(-50.0000000000015,-24.8749999999714,-20.)); +#1333=CARTESIAN_POINT('',(-50.2000000000321,-24.8749999999714,-28.5)); +#1334=CARTESIAN_POINT('Origin',(49.9999999999985,-24.8749999999776,20.)); +#1335=CARTESIAN_POINT('',(58.5023526155995,-27.3749999999709,20.)); +#1336=CARTESIAN_POINT('',(50.2000000000286,-27.3749999999714,28.5)); +#1337=CARTESIAN_POINT('Origin',(49.9999999999983,-27.3749999999688,20.)); +#1338=CARTESIAN_POINT('',(58.5023526155997,-24.8749999999781,20.)); +#1339=CARTESIAN_POINT('',(58.5023526155997,-24.8749999999781,20.)); +#1340=CARTESIAN_POINT('',(50.2000000000288,-24.8749999999776,28.5)); +#1341=CARTESIAN_POINT('Origin',(49.9999999999985,-24.8749999999688,20.)); +#1342=CARTESIAN_POINT('',(50.2000000000287,-24.8749999999776,28.5)); +#1343=CARTESIAN_POINT('Origin',(49.9999999999985,-24.8749999999776,-20.)); +#1344=CARTESIAN_POINT('',(50.2000000000286,-27.3749999999714,-28.5)); +#1345=CARTESIAN_POINT('',(58.5023526155995,-27.3749999999709,-20.)); +#1346=CARTESIAN_POINT('Origin',(49.9999999999983,-27.3749999999688,-20.)); +#1347=CARTESIAN_POINT('',(50.2000000000288,-24.8749999999776,-28.5)); +#1348=CARTESIAN_POINT('',(50.2000000000287,-24.8749999999776,-28.5)); +#1349=CARTESIAN_POINT('',(58.5023526155997,-24.8749999999781,-20.)); +#1350=CARTESIAN_POINT('Origin',(49.9999999999985,-24.8749999999688,-20.)); +#1351=CARTESIAN_POINT('',(58.5023526155997,-24.8749999999781,-20.)); +#1352=CARTESIAN_POINT('Origin',(58.5023526155997,-24.8749999999781,20.)); +#1353=CARTESIAN_POINT('',(58.5023526155995,-27.3749999999709,10.)); +#1354=CARTESIAN_POINT('',(58.5023526155997,-24.8749999999709,10.)); +#1355=CARTESIAN_POINT('Origin',(-52.299999999971,-27.3749999999713,28.5)); +#1356=CARTESIAN_POINT('',(-33.5999999999717,-27.3749999999724,28.5)); +#1357=CARTESIAN_POINT('',(-30.9999999999703,-27.3749999999726,28.5)); +#1358=CARTESIAN_POINT('',(-33.5999999999715,-24.8749999999724,28.5)); +#1359=CARTESIAN_POINT('',(-33.5999999999717,-27.3749999999724,28.5)); +#1360=CARTESIAN_POINT('',(-30.9999999999701,-24.8749999999726,28.5)); +#1361=CARTESIAN_POINT('Origin',(-30.9999999999703,-27.3749999999726,0.)); +#1362=CARTESIAN_POINT('',(-33.5999999999717,-27.3749999999724,-28.5)); +#1363=CARTESIAN_POINT('',(-30.9999999999703,-27.3749999999726,-28.5)); +#1364=CARTESIAN_POINT('',(-33.5999999999717,-27.3749999999724,0.)); +#1365=CARTESIAN_POINT('Origin',(70.9999999999765,-24.8749999999701,0.)); +#1366=CARTESIAN_POINT('',(33.5999999999779,-24.8749999999724,-28.5)); +#1367=CARTESIAN_POINT('',(30.9999999999765,-24.8749999999726,-28.5)); +#1368=CARTESIAN_POINT('',(33.5999999999779,-24.8749999999724,28.5)); +#1369=CARTESIAN_POINT('',(33.5999999999779,-24.8749999999724,0.)); +#1370=CARTESIAN_POINT('',(30.9999999999765,-24.8749999999726,28.5)); +#1371=CARTESIAN_POINT('Origin',(-52.299999999971,-27.3749999999713,-28.5)); +#1372=CARTESIAN_POINT('',(-33.5999999999715,-24.8749999999724,-28.5)); +#1373=CARTESIAN_POINT('',(-30.9999999999701,-24.8749999999726,-28.5)); +#1374=CARTESIAN_POINT('',(-33.5999999999717,-27.3749999999724,-28.5)); +#1375=CARTESIAN_POINT('Origin',(-30.9999999999701,-24.8749999999726,0.)); +#1376=CARTESIAN_POINT('',(-33.5999999999715,-24.8749999999724,0.)); +#1377=CARTESIAN_POINT('Origin',(70.9999999999766,-27.3749999999701,0.)); +#1378=CARTESIAN_POINT('',(33.5999999999781,-27.3749999999724,28.5)); +#1379=CARTESIAN_POINT('',(30.9999999999766,-27.3749999999726,28.5)); +#1380=CARTESIAN_POINT('',(33.5999999999781,-27.3749999999724,-28.5)); +#1381=CARTESIAN_POINT('',(33.5999999999781,-27.3749999999724,0.)); +#1382=CARTESIAN_POINT('',(30.9999999999766,-27.3749999999726,-28.5)); +#1383=CARTESIAN_POINT('Origin',(21.6506354172176,-8.62500000029315,12.5000001862645)); +#1384=CARTESIAN_POINT('',(21.6506354172176,29.8750000000439,10.9000001862645)); +#1385=CARTESIAN_POINT('Origin',(21.6506354172176,29.8750000000274,12.5000001862645)); +#1386=CARTESIAN_POINT('',(21.6506354172176,27.3750000000274,10.9000001862645)); +#1387=CARTESIAN_POINT('',(21.6506354172176,-8.62500000029315,10.9000001862645)); +#1388=CARTESIAN_POINT('Origin',(21.6506354172176,27.3750000000274,12.5000001862645)); +#1389=CARTESIAN_POINT('Origin',(-1.2925216449654E-11,-8.62500000029315, +-25.000000372529)); +#1390=CARTESIAN_POINT('',(-1.29250205061661E-11,29.8750000000439,-26.600000372529)); +#1391=CARTESIAN_POINT('Origin',(-1.2925216449654E-11,29.8750000000274,-25.000000372529)); +#1392=CARTESIAN_POINT('',(-1.29254123931419E-11,27.3750000000274,-26.600000372529)); +#1393=CARTESIAN_POINT('',(-1.29250205061661E-11,-8.62500000029315,-26.600000372529)); +#1394=CARTESIAN_POINT('Origin',(-1.2925216449654E-11,27.3750000000274,-25.000000372529)); +#1395=CARTESIAN_POINT('Origin',(-21.6506354172435,-8.62500000029315,12.5000001862645)); +#1396=CARTESIAN_POINT('',(-21.6506354172435,29.8750000000439,10.9000001862645)); +#1397=CARTESIAN_POINT('Origin',(-21.6506354172435,29.8750000000274,12.5000001862645)); +#1398=CARTESIAN_POINT('',(-21.6506354172435,27.3750000000274,10.9000001862645)); +#1399=CARTESIAN_POINT('',(-21.6506354172435,-8.62500000029315,10.9000001862645)); +#1400=CARTESIAN_POINT('Origin',(-21.6506354172435,27.3750000000274,12.5000001862645)); +#1401=CARTESIAN_POINT('Origin',(-21.6506354172435,-8.62500000029315,-12.5000001862645)); +#1402=CARTESIAN_POINT('',(-21.6506354172435,29.8750000000439,-14.1000001862645)); +#1403=CARTESIAN_POINT('Origin',(-21.6506354172435,29.8750000000274,-12.5000001862645)); +#1404=CARTESIAN_POINT('',(-21.6506354172435,27.3750000000274,-14.1000001862645)); +#1405=CARTESIAN_POINT('',(-21.6506354172435,-8.62500000029315,-14.1000001862645)); +#1406=CARTESIAN_POINT('Origin',(-21.6506354172435,27.3750000000274,-12.5000001862645)); +#1407=CARTESIAN_POINT('Origin',(21.6506354172177,-8.62500000029315,-12.5000001862645)); +#1408=CARTESIAN_POINT('',(21.6506354172177,29.8750000000439,-14.1000001862645)); +#1409=CARTESIAN_POINT('Origin',(21.6506354172177,29.8750000000274,-12.5000001862645)); +#1410=CARTESIAN_POINT('',(21.6506354172177,27.3750000000274,-14.1000001862645)); +#1411=CARTESIAN_POINT('',(21.6506354172177,-8.62500000029315,-14.1000001862645)); +#1412=CARTESIAN_POINT('Origin',(21.6506354172177,27.3750000000274,-12.5000001862645)); +#1413=CARTESIAN_POINT('Origin',(-1.29282780666975E-11,-8.62500000029315, +25.000000372529)); +#1414=CARTESIAN_POINT('',(-1.29280821232096E-11,29.8750000000439,23.400000372529)); +#1415=CARTESIAN_POINT('Origin',(-1.29282780666975E-11,29.8750000000274, +25.000000372529)); +#1416=CARTESIAN_POINT('',(-1.29284740101854E-11,27.3750000000274,23.400000372529)); +#1417=CARTESIAN_POINT('',(-1.29280821232096E-11,-8.62500000029315,23.400000372529)); +#1418=CARTESIAN_POINT('Origin',(-1.29282780666975E-11,27.3750000000274, +25.000000372529)); +#1419=CARTESIAN_POINT('Origin',(-1.2925216449654E-11,29.8749999997069,0.)); +#1420=CARTESIAN_POINT('',(21.4999999999871,29.8749999997069,-2.63299061816681E-15)); +#1421=CARTESIAN_POINT('Origin',(-1.2925216449654E-11,29.8750000000274,0.)); +#1422=CARTESIAN_POINT('',(21.4999999999871,27.3750000000274,-2.63299061816681E-15)); +#1423=CARTESIAN_POINT('',(21.4999999999871,29.8749999997069,2.63299061816681E-15)); +#1424=CARTESIAN_POINT('Origin',(-1.2925216449654E-11,27.3750000000274,0.)); +#1425=CARTESIAN_POINT('Origin',(33.5999999999779,-24.7749999999724,0.)); +#1426=CARTESIAN_POINT('',(33.4999999999779,-24.7749999999724,28.5)); +#1427=CARTESIAN_POINT('Origin',(33.5999999999779,-24.7749999999724,28.5)); +#1428=CARTESIAN_POINT('',(33.4999999999779,-24.7749999999724,-28.5)); +#1429=CARTESIAN_POINT('Origin',(33.5999999999779,-24.7749999999724,-28.5)); +#1430=CARTESIAN_POINT('',(33.4999999999779,-24.7749999999724,0.)); +#1431=CARTESIAN_POINT('Origin',(33.4999999999766,-27.3749999999738,0.)); +#1432=CARTESIAN_POINT('',(33.5000000000033,27.2750000000251,-28.5)); +#1433=CARTESIAN_POINT('',(33.5000000000034,27.3750000000262,-28.5)); +#1434=CARTESIAN_POINT('',(33.5000000000033,27.2750000000251,28.5)); +#1435=CARTESIAN_POINT('',(33.5000000000033,27.2750000000251,0.)); +#1436=CARTESIAN_POINT('',(33.5000000000034,27.3750000000262,28.5)); +#1437=CARTESIAN_POINT('Origin',(-33.5999999999715,-24.7749999999724,0.)); +#1438=CARTESIAN_POINT('',(-33.4999999999715,-24.7749999999724,28.5)); +#1439=CARTESIAN_POINT('Origin',(-33.5999999999715,-24.7749999999724,28.5)); +#1440=CARTESIAN_POINT('',(-33.4999999999715,-24.7749999999724,-28.5)); +#1441=CARTESIAN_POINT('',(-33.4999999999715,-24.7749999999724,0.)); +#1442=CARTESIAN_POINT('Origin',(-33.5999999999715,-24.7749999999724,-28.5)); +#1443=CARTESIAN_POINT('Origin',(-33.499999999997,27.3750000000262,0.)); +#1444=CARTESIAN_POINT('',(-33.4999999999969,27.2749999993861,28.5)); +#1445=CARTESIAN_POINT('',(-33.499999999997,27.3750000000262,28.5)); +#1446=CARTESIAN_POINT('',(-33.4999999999969,27.2749999993861,-28.5)); +#1447=CARTESIAN_POINT('',(-33.4999999999969,27.2749999993861,0.)); +#1448=CARTESIAN_POINT('',(-33.499999999997,27.3750000000262,-28.5)); +#1449=CARTESIAN_POINT('Origin',(30.9000000000033,27.2750000000264,0.)); +#1450=CARTESIAN_POINT('',(30.8999999999764,29.8750000000264,28.5)); +#1451=CARTESIAN_POINT('Origin',(30.9000000000033,27.2750000000264,28.5)); +#1452=CARTESIAN_POINT('',(30.8999999999764,29.8749999993877,-28.5)); +#1453=CARTESIAN_POINT('Origin',(30.9000000000033,27.2750000000264,-28.5)); +#1454=CARTESIAN_POINT('',(30.8999999999764,29.8750000000264,0.)); +#1455=CARTESIAN_POINT('Origin',(30.9999999999775,29.8750000000274,0.)); +#1456=CARTESIAN_POINT('',(-30.9000000000238,29.8750000000264,-28.5)); +#1457=CARTESIAN_POINT('',(-28.5000000000227,29.8750000000016,-28.5)); +#1458=CARTESIAN_POINT('',(-30.9000000000238,29.8749999993873,28.5)); +#1459=CARTESIAN_POINT('',(-30.9000000000238,29.8749999993873,0.)); +#1460=CARTESIAN_POINT('',(28.4999999999773,29.8750000000015,28.5)); +#1461=CARTESIAN_POINT('Origin',(-30.8999999999969,27.2749999993873,0.)); +#1462=CARTESIAN_POINT('Origin',(-30.8999999999969,27.2749999993873,28.5)); +#1463=CARTESIAN_POINT('Origin',(-30.8999999999969,27.2749999993873,-28.5)); +#1464=CARTESIAN_POINT('Origin',(33.5999999999779,-24.7749999999724,0.)); +#1465=CARTESIAN_POINT('',(30.9999999999779,-24.7749999999712,28.5)); +#1466=CARTESIAN_POINT('Origin',(33.5999999999779,-24.7749999999724,28.5)); +#1467=CARTESIAN_POINT('',(30.9999999999779,-24.7749999999712,-28.5)); +#1468=CARTESIAN_POINT('',(30.9999999999779,-24.7749999999712,0.)); +#1469=CARTESIAN_POINT('Origin',(33.5999999999779,-24.7749999999724,-28.5)); +#1470=CARTESIAN_POINT('Origin',(30.9999999999766,-27.3749999999726,0.)); +#1471=CARTESIAN_POINT('',(31.0000000000033,27.2750000000263,28.5)); +#1472=CARTESIAN_POINT('',(31.0000000000034,27.3750000000274,28.5)); +#1473=CARTESIAN_POINT('',(31.0000000000033,27.2750000000263,-28.5)); +#1474=CARTESIAN_POINT('',(31.0000000000033,27.2750000000263,0.)); +#1475=CARTESIAN_POINT('',(31.0000000000034,27.3750000000274,-28.5)); +#1476=CARTESIAN_POINT('Origin',(-33.5999999999715,-24.7749999999724,0.)); +#1477=CARTESIAN_POINT('',(-30.9999999999715,-24.7749999999712,28.5)); +#1478=CARTESIAN_POINT('Origin',(-33.5999999999715,-24.7749999999724,28.5)); +#1479=CARTESIAN_POINT('',(-30.9999999999715,-24.7749999999712,-28.5)); +#1480=CARTESIAN_POINT('Origin',(-33.5999999999715,-24.7749999999724,-28.5)); +#1481=CARTESIAN_POINT('',(-30.9999999999715,-24.7749999999712,0.)); +#1482=CARTESIAN_POINT('Origin',(-30.999999999997,27.3750000000274,0.)); +#1483=CARTESIAN_POINT('',(-30.9999999999969,27.2749999993873,-28.5)); +#1484=CARTESIAN_POINT('',(-30.999999999997,27.3750000000274,-28.5)); +#1485=CARTESIAN_POINT('',(-30.9999999999969,27.2749999993873,28.5)); +#1486=CARTESIAN_POINT('',(-30.9999999999969,27.2749999993873,0.)); +#1487=CARTESIAN_POINT('',(-30.999999999997,27.3750000000274,28.5)); +#1488=CARTESIAN_POINT('Origin',(30.9000000000033,27.2750000000264,0.)); +#1489=CARTESIAN_POINT('',(30.9000000000023,27.3750000000264,28.5)); +#1490=CARTESIAN_POINT('Origin',(30.9000000000033,27.2750000000264,28.5)); +#1491=CARTESIAN_POINT('',(30.9000000000023,27.3749999993877,-28.5)); +#1492=CARTESIAN_POINT('',(30.9000000000023,27.3750000000264,0.)); +#1493=CARTESIAN_POINT('Origin',(30.9000000000033,27.2750000000264,-28.5)); +#1494=CARTESIAN_POINT('Origin',(31.0000000000034,27.3750000000274,0.)); +#1495=CARTESIAN_POINT('',(-30.899999999998,27.3749999993873,28.5)); +#1496=CARTESIAN_POINT('',(28.5000000000032,27.3750000000015,28.5)); +#1497=CARTESIAN_POINT('',(-30.899999999998,27.3750000000264,-28.5)); +#1498=CARTESIAN_POINT('',(-30.899999999998,27.3749999993873,0.)); +#1499=CARTESIAN_POINT('',(-28.4999999999968,27.3750000000016,-28.5)); +#1500=CARTESIAN_POINT('Origin',(-30.8999999999969,27.2749999993873,0.)); +#1501=CARTESIAN_POINT('Origin',(-30.8999999999969,27.2749999993873,28.5)); +#1502=CARTESIAN_POINT('Origin',(-30.8999999999969,27.2749999993873,-28.5)); +#1503=CARTESIAN_POINT('Origin',(31.7615223688925,-26.6134776310571,28.5)); +#1504=CARTESIAN_POINT('',(33.5999999999781,-27.3749999999724,28.5)); +#1505=CARTESIAN_POINT('',(30.9999999999779,-24.7749999999712,28.5)); +#1506=CARTESIAN_POINT('Origin',(31.7615223688925,-26.6134776310571,-28.5)); +#1507=CARTESIAN_POINT('',(30.9999999999779,-24.7749999999712,-28.5)); +#1508=CARTESIAN_POINT('',(33.5999999999781,-27.3749999999724,-28.5)); +#1509=CARTESIAN_POINT('Origin',(30.9999999999906,1.25000000002757,-28.5)); +#1510=CARTESIAN_POINT('',(31.0000000000033,27.2750000000263,-28.5)); +#1511=CARTESIAN_POINT('Origin',(30.9999999999906,1.25000000002757,28.5)); +#1512=CARTESIAN_POINT('',(31.0000000000033,27.2750000000263,28.5)); +#1513=CARTESIAN_POINT('Origin',(52.2999999999773,-27.3749999999713,28.5)); +#1514=CARTESIAN_POINT('Origin',(52.2999999999773,-27.3749999999713,-28.5)); +#1515=CARTESIAN_POINT('Origin',(-31.7615223688861,-26.6134776310571,28.5)); +#1516=CARTESIAN_POINT('',(-30.9999999999715,-24.7749999999712,28.5)); +#1517=CARTESIAN_POINT('Origin',(-31.7615223688861,-26.6134776310571,-28.5)); +#1518=CARTESIAN_POINT('',(-30.9999999999715,-24.7749999999712,-28.5)); +#1519=CARTESIAN_POINT('Origin',(-30.9999999999842,1.24999999970806,28.5)); +#1520=CARTESIAN_POINT('',(-30.9999999999969,27.2749999993873,28.5)); +#1521=CARTESIAN_POINT('Origin',(-30.9999999999842,1.24999999970806,-28.5)); +#1522=CARTESIAN_POINT('',(-30.9999999999969,27.2749999993873,-28.5)); +#1523=CARTESIAN_POINT('Origin',(30.9707106781216,27.3457106781454,28.5)); +#1524=CARTESIAN_POINT('',(30.9000000000023,27.3750000000264,28.5)); +#1525=CARTESIAN_POINT('Origin',(30.9707106781216,27.3457106781454,-28.5)); +#1526=CARTESIAN_POINT('',(30.9000000000023,27.3749999993877,-28.5)); +#1527=CARTESIAN_POINT('Origin',(2.1449508835758E-12,27.374999999707,-28.5)); +#1528=CARTESIAN_POINT('',(-30.899999999998,27.3750000000264,-28.5)); +#1529=CARTESIAN_POINT('Origin',(2.1493917756743E-12,27.3749999997069,28.5)); +#1530=CARTESIAN_POINT('',(-30.899999999998,27.3749999993873,28.5)); +#1531=CARTESIAN_POINT('Origin',(-30.970710678116,27.3457106775056,28.5)); +#1532=CARTESIAN_POINT('Origin',(-30.970710678116,27.3457106775056,-28.5)); +#1533=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1537, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1534=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1537, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1535=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1533)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1537,#1539,#1540)) +REPRESENTATION_CONTEXT('','3D') +); +#1536=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1534)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1537,#1539,#1540)) +REPRESENTATION_CONTEXT('','3D') +); +#1537=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#1538=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT($,.METRE.) +); +#1539=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#1540=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#1541=SHAPE_DEFINITION_REPRESENTATION(#1542,#1543); +#1542=PRODUCT_DEFINITION_SHAPE('',$,#1545); +#1543=SHAPE_REPRESENTATION('',(#913),#1535); +#1544=PRODUCT_DEFINITION_CONTEXT('part definition',#1549,'design'); +#1545=PRODUCT_DEFINITION('link0-1','link0-1 v1',#1546,#1544); +#1546=PRODUCT_DEFINITION_FORMATION('',$,#1551); +#1547=PRODUCT_RELATED_PRODUCT_CATEGORY('link0-1 v1','link0-1 v1',(#1551)); +#1548=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#1549); +#1549=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#1550=PRODUCT_CONTEXT('part definition',#1549,'mechanical'); +#1551=PRODUCT('link0-1','link0-1 v1',$,(#1550)); +#1552=PRESENTATION_STYLE_ASSIGNMENT((#1553)); +#1553=SURFACE_STYLE_USAGE(.BOTH.,#1554); +#1554=SURFACE_SIDE_STYLE('',(#1555)); +#1555=SURFACE_STYLE_FILL_AREA(#1556); +#1556=FILL_AREA_STYLE('Aluminum - Satin',(#1557)); +#1557=FILL_AREA_STYLE_COLOUR('Aluminum - Satin',#1558); +#1558=COLOUR_RGB('Aluminum - Satin',0.96078431372549,0.96078431372549,0.964705882352941); +ENDSEC; +END-ISO-10303-21; diff --git a/hardware/follower_STEPs/link1-2_v0.2.0.step b/hardware/follower_STEPs/link1-2_v0.2.0.step new file mode 100644 index 0000000000000000000000000000000000000000..893a46877e2356a642dafa98bafd80f43ff1e1cf --- /dev/null +++ b/hardware/follower_STEPs/link1-2_v0.2.0.step @@ -0,0 +1,1571 @@ +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 */ 'link1-2_v0.2.0.step', +/* time_stamp */ '2025-10-08T21:02:25+02:00', +/* author */ (''), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v20.1', +/* originating_system */ 'Autodesk Translation Framework v14.17.0.0', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#1483); +#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#1490,#12); +#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#1482); +#13=STYLED_ITEM('',(#1500),#14); +#14=MANIFOLD_SOLID_BREP('Body1',#867); +#15=FACE_BOUND('',#146,.T.); +#16=FACE_BOUND('',#147,.T.); +#17=FACE_BOUND('',#148,.T.); +#18=FACE_BOUND('',#149,.T.); +#19=FACE_BOUND('',#150,.T.); +#20=FACE_BOUND('',#151,.T.); +#21=FACE_BOUND('',#152,.T.); +#22=FACE_BOUND('',#153,.T.); +#23=FACE_BOUND('',#156,.T.); +#24=FACE_BOUND('',#157,.T.); +#25=FACE_BOUND('',#158,.T.); +#26=FACE_BOUND('',#159,.T.); +#27=FACE_BOUND('',#160,.T.); +#28=FACE_BOUND('',#161,.T.); +#29=FACE_BOUND('',#162,.T.); +#30=FACE_BOUND('',#164,.T.); +#31=FACE_BOUND('',#165,.T.); +#32=FACE_BOUND('',#166,.T.); +#33=FACE_BOUND('',#167,.T.); +#34=FACE_BOUND('',#168,.T.); +#35=FACE_BOUND('',#169,.T.); +#36=FACE_BOUND('',#170,.T.); +#37=FACE_BOUND('',#174,.T.); +#38=FACE_BOUND('',#175,.T.); +#39=FACE_BOUND('',#176,.T.); +#40=FACE_BOUND('',#177,.T.); +#41=FACE_BOUND('',#178,.T.); +#42=FACE_BOUND('',#179,.T.); +#43=FACE_BOUND('',#180,.T.); +#44=FACE_BOUND('',#183,.T.); +#45=FACE_BOUND('',#184,.T.); +#46=FACE_BOUND('',#185,.T.); +#47=FACE_BOUND('',#186,.T.); +#48=FACE_BOUND('',#187,.T.); +#49=FACE_BOUND('',#188,.T.); +#50=FACE_BOUND('',#189,.T.); +#51=FACE_BOUND('',#190,.T.); +#52=FACE_BOUND('',#192,.T.); +#53=FACE_BOUND('',#193,.T.); +#54=FACE_BOUND('',#194,.T.); +#55=FACE_BOUND('',#195,.T.); +#56=FACE_BOUND('',#196,.T.); +#57=FACE_BOUND('',#197,.T.); +#58=FACE_BOUND('',#198,.T.); +#59=PLANE('',#947); +#60=PLANE('',#952); +#61=PLANE('',#953); +#62=PLANE('',#954); +#63=PLANE('',#958); +#64=PLANE('',#966); +#65=PLANE('',#973); +#66=PLANE('',#975); +#67=PLANE('',#976); +#68=PLANE('',#979); +#69=PLANE('',#981); +#70=PLANE('',#982); +#71=FACE_OUTER_BOUND('',#113,.T.); +#72=FACE_OUTER_BOUND('',#114,.T.); +#73=FACE_OUTER_BOUND('',#115,.T.); +#74=FACE_OUTER_BOUND('',#116,.T.); +#75=FACE_OUTER_BOUND('',#117,.T.); +#76=FACE_OUTER_BOUND('',#118,.T.); +#77=FACE_OUTER_BOUND('',#119,.T.); +#78=FACE_OUTER_BOUND('',#120,.T.); +#79=FACE_OUTER_BOUND('',#121,.T.); +#80=FACE_OUTER_BOUND('',#122,.T.); +#81=FACE_OUTER_BOUND('',#123,.T.); +#82=FACE_OUTER_BOUND('',#124,.T.); +#83=FACE_OUTER_BOUND('',#125,.T.); +#84=FACE_OUTER_BOUND('',#126,.T.); +#85=FACE_OUTER_BOUND('',#127,.T.); +#86=FACE_OUTER_BOUND('',#128,.T.); +#87=FACE_OUTER_BOUND('',#129,.T.); +#88=FACE_OUTER_BOUND('',#130,.T.); +#89=FACE_OUTER_BOUND('',#131,.T.); +#90=FACE_OUTER_BOUND('',#132,.T.); +#91=FACE_OUTER_BOUND('',#133,.T.); +#92=FACE_OUTER_BOUND('',#134,.T.); +#93=FACE_OUTER_BOUND('',#135,.T.); +#94=FACE_OUTER_BOUND('',#136,.T.); +#95=FACE_OUTER_BOUND('',#137,.T.); +#96=FACE_OUTER_BOUND('',#138,.T.); +#97=FACE_OUTER_BOUND('',#139,.T.); +#98=FACE_OUTER_BOUND('',#140,.T.); +#99=FACE_OUTER_BOUND('',#141,.T.); +#100=FACE_OUTER_BOUND('',#142,.T.); +#101=FACE_OUTER_BOUND('',#143,.T.); +#102=FACE_OUTER_BOUND('',#144,.T.); +#103=FACE_OUTER_BOUND('',#145,.T.); +#104=FACE_OUTER_BOUND('',#154,.T.); +#105=FACE_OUTER_BOUND('',#155,.T.); +#106=FACE_OUTER_BOUND('',#163,.T.); +#107=FACE_OUTER_BOUND('',#171,.T.); +#108=FACE_OUTER_BOUND('',#172,.T.); +#109=FACE_OUTER_BOUND('',#173,.T.); +#110=FACE_OUTER_BOUND('',#181,.T.); +#111=FACE_OUTER_BOUND('',#182,.T.); +#112=FACE_OUTER_BOUND('',#191,.T.); +#113=EDGE_LOOP('',(#563,#564,#565,#566)); +#114=EDGE_LOOP('',(#567,#568,#569,#570)); +#115=EDGE_LOOP('',(#571,#572,#573,#574)); +#116=EDGE_LOOP('',(#575,#576,#577,#578)); +#117=EDGE_LOOP('',(#579,#580,#581,#582)); +#118=EDGE_LOOP('',(#583,#584,#585,#586)); +#119=EDGE_LOOP('',(#587,#588,#589,#590)); +#120=EDGE_LOOP('',(#591,#592,#593,#594)); +#121=EDGE_LOOP('',(#595,#596,#597,#598)); +#122=EDGE_LOOP('',(#599,#600,#601,#602)); +#123=EDGE_LOOP('',(#603,#604,#605,#606)); +#124=EDGE_LOOP('',(#607,#608,#609,#610)); +#125=EDGE_LOOP('',(#611,#612,#613,#614)); +#126=EDGE_LOOP('',(#615,#616,#617,#618)); +#127=EDGE_LOOP('',(#619,#620,#621,#622)); +#128=EDGE_LOOP('',(#623,#624,#625,#626)); +#129=EDGE_LOOP('',(#627,#628,#629,#630)); +#130=EDGE_LOOP('',(#631,#632,#633,#634)); +#131=EDGE_LOOP('',(#635,#636,#637,#638)); +#132=EDGE_LOOP('',(#639,#640,#641,#642)); +#133=EDGE_LOOP('',(#643,#644,#645,#646)); +#134=EDGE_LOOP('',(#647,#648,#649,#650)); +#135=EDGE_LOOP('',(#651,#652,#653,#654,#655,#656,#657,#658)); +#136=EDGE_LOOP('',(#659,#660,#661,#662)); +#137=EDGE_LOOP('',(#663,#664,#665,#666)); +#138=EDGE_LOOP('',(#667,#668,#669,#670)); +#139=EDGE_LOOP('',(#671,#672,#673,#674)); +#140=EDGE_LOOP('',(#675,#676,#677,#678,#679,#680,#681,#682,#683,#684,#685, +#686)); +#141=EDGE_LOOP('',(#687,#688,#689,#690)); +#142=EDGE_LOOP('',(#691,#692,#693,#694)); +#143=EDGE_LOOP('',(#695,#696,#697,#698)); +#144=EDGE_LOOP('',(#699,#700,#701,#702)); +#145=EDGE_LOOP('',(#703,#704,#705,#706)); +#146=EDGE_LOOP('',(#707)); +#147=EDGE_LOOP('',(#708)); +#148=EDGE_LOOP('',(#709)); +#149=EDGE_LOOP('',(#710)); +#150=EDGE_LOOP('',(#711)); +#151=EDGE_LOOP('',(#712)); +#152=EDGE_LOOP('',(#713)); +#153=EDGE_LOOP('',(#714)); +#154=EDGE_LOOP('',(#715,#716,#717,#718)); +#155=EDGE_LOOP('',(#719,#720,#721,#722,#723,#724)); +#156=EDGE_LOOP('',(#725)); +#157=EDGE_LOOP('',(#726)); +#158=EDGE_LOOP('',(#727)); +#159=EDGE_LOOP('',(#728)); +#160=EDGE_LOOP('',(#729)); +#161=EDGE_LOOP('',(#730)); +#162=EDGE_LOOP('',(#731)); +#163=EDGE_LOOP('',(#732,#733,#734,#735,#736,#737)); +#164=EDGE_LOOP('',(#738)); +#165=EDGE_LOOP('',(#739)); +#166=EDGE_LOOP('',(#740)); +#167=EDGE_LOOP('',(#741)); +#168=EDGE_LOOP('',(#742)); +#169=EDGE_LOOP('',(#743)); +#170=EDGE_LOOP('',(#744)); +#171=EDGE_LOOP('',(#745,#746,#747,#748)); +#172=EDGE_LOOP('',(#749,#750,#751,#752)); +#173=EDGE_LOOP('',(#753,#754,#755,#756,#757,#758)); +#174=EDGE_LOOP('',(#759)); +#175=EDGE_LOOP('',(#760)); +#176=EDGE_LOOP('',(#761)); +#177=EDGE_LOOP('',(#762)); +#178=EDGE_LOOP('',(#763)); +#179=EDGE_LOOP('',(#764)); +#180=EDGE_LOOP('',(#765)); +#181=EDGE_LOOP('',(#766,#767,#768,#769)); +#182=EDGE_LOOP('',(#770,#771,#772,#773)); +#183=EDGE_LOOP('',(#774)); +#184=EDGE_LOOP('',(#775)); +#185=EDGE_LOOP('',(#776)); +#186=EDGE_LOOP('',(#777)); +#187=EDGE_LOOP('',(#778)); +#188=EDGE_LOOP('',(#779)); +#189=EDGE_LOOP('',(#780)); +#190=EDGE_LOOP('',(#781)); +#191=EDGE_LOOP('',(#782,#783,#784,#785,#786,#787)); +#192=EDGE_LOOP('',(#788)); +#193=EDGE_LOOP('',(#789)); +#194=EDGE_LOOP('',(#790)); +#195=EDGE_LOOP('',(#791)); +#196=EDGE_LOOP('',(#792)); +#197=EDGE_LOOP('',(#793)); +#198=EDGE_LOOP('',(#794)); +#199=LINE('',#1250,#255); +#200=LINE('',#1256,#256); +#201=LINE('',#1262,#257); +#202=LINE('',#1268,#258); +#203=LINE('',#1274,#259); +#204=LINE('',#1280,#260); +#205=LINE('',#1286,#261); +#206=LINE('',#1292,#262); +#207=LINE('',#1298,#263); +#208=LINE('',#1304,#264); +#209=LINE('',#1310,#265); +#210=LINE('',#1316,#266); +#211=LINE('',#1322,#267); +#212=LINE('',#1328,#268); +#213=LINE('',#1334,#269); +#214=LINE('',#1340,#270); +#215=LINE('',#1346,#271); +#216=LINE('',#1352,#272); +#217=LINE('',#1358,#273); +#218=LINE('',#1364,#274); +#219=LINE('',#1371,#275); +#220=LINE('',#1374,#276); +#221=LINE('',#1380,#277); +#222=LINE('',#1383,#278); +#223=LINE('',#1389,#279); +#224=LINE('',#1393,#280); +#225=LINE('',#1397,#281); +#226=LINE('',#1400,#282); +#227=LINE('',#1403,#283); +#228=LINE('',#1405,#284); +#229=LINE('',#1406,#285); +#230=LINE('',#1409,#286); +#231=LINE('',#1411,#287); +#232=LINE('',#1412,#288); +#233=LINE('',#1415,#289); +#234=LINE('',#1417,#290); +#235=LINE('',#1418,#291); +#236=LINE('',#1426,#292); +#237=LINE('',#1428,#293); +#238=LINE('',#1432,#294); +#239=LINE('',#1435,#295); +#240=LINE('',#1437,#296); +#241=LINE('',#1440,#297); +#242=LINE('',#1446,#298); +#243=LINE('',#1448,#299); +#244=LINE('',#1449,#300); +#245=LINE('',#1454,#301); +#246=LINE('',#1460,#302); +#247=LINE('',#1463,#303); +#248=LINE('',#1464,#304); +#249=LINE('',#1466,#305); +#250=LINE('',#1467,#306); +#251=LINE('',#1469,#307); +#252=LINE('',#1473,#308); +#253=LINE('',#1476,#309); +#254=LINE('',#1477,#310); +#255=VECTOR('',#989,1.2645); +#256=VECTOR('',#996,1.2645); +#257=VECTOR('',#1003,1.6); +#258=VECTOR('',#1010,1.6); +#259=VECTOR('',#1017,1.6); +#260=VECTOR('',#1024,1.6); +#261=VECTOR('',#1031,1.6); +#262=VECTOR('',#1038,1.6); +#263=VECTOR('',#1045,1.6); +#264=VECTOR('',#1052,1.6); +#265=VECTOR('',#1059,1.6); +#266=VECTOR('',#1066,1.6); +#267=VECTOR('',#1073,1.6); +#268=VECTOR('',#1080,1.6); +#269=VECTOR('',#1087,1.6); +#270=VECTOR('',#1094,1.6); +#271=VECTOR('',#1101,1.6); +#272=VECTOR('',#1108,1.6); +#273=VECTOR('',#1115,1.6); +#274=VECTOR('',#1122,1.6); +#275=VECTOR('',#1129,10.); +#276=VECTOR('',#1132,10.); +#277=VECTOR('',#1137,10.); +#278=VECTOR('',#1140,10.); +#279=VECTOR('',#1145,10.); +#280=VECTOR('',#1148,10.); +#281=VECTOR('',#1151,10.); +#282=VECTOR('',#1154,10.); +#283=VECTOR('',#1157,10.); +#284=VECTOR('',#1158,10.); +#285=VECTOR('',#1159,10.); +#286=VECTOR('',#1162,10.); +#287=VECTOR('',#1163,10.); +#288=VECTOR('',#1164,10.); +#289=VECTOR('',#1167,10.); +#290=VECTOR('',#1168,10.); +#291=VECTOR('',#1169,10.); +#292=VECTOR('',#1180,10.); +#293=VECTOR('',#1181,10.); +#294=VECTOR('',#1184,10.); +#295=VECTOR('',#1187,10.); +#296=VECTOR('',#1188,10.); +#297=VECTOR('',#1191,10.); +#298=VECTOR('',#1198,10.); +#299=VECTOR('',#1201,10.); +#300=VECTOR('',#1202,10.); +#301=VECTOR('',#1207,7.); +#302=VECTOR('',#1214,7.); +#303=VECTOR('',#1219,10.); +#304=VECTOR('',#1220,10.); +#305=VECTOR('',#1223,10.); +#306=VECTOR('',#1224,10.); +#307=VECTOR('',#1227,10.); +#308=VECTOR('',#1234,10.); +#309=VECTOR('',#1239,10.); +#310=VECTOR('',#1240,10.); +#311=CIRCLE('',#882,1.2645); +#312=CIRCLE('',#883,1.2645); +#313=CIRCLE('',#885,1.2645); +#314=CIRCLE('',#886,1.2645); +#315=CIRCLE('',#888,1.6); +#316=CIRCLE('',#889,1.6); +#317=CIRCLE('',#891,1.6); +#318=CIRCLE('',#892,1.6); +#319=CIRCLE('',#894,1.6); +#320=CIRCLE('',#895,1.6); +#321=CIRCLE('',#897,1.6); +#322=CIRCLE('',#898,1.6); +#323=CIRCLE('',#900,1.6); +#324=CIRCLE('',#901,1.6); +#325=CIRCLE('',#903,1.6); +#326=CIRCLE('',#904,1.6); +#327=CIRCLE('',#906,1.6); +#328=CIRCLE('',#907,1.6); +#329=CIRCLE('',#909,1.6); +#330=CIRCLE('',#910,1.6); +#331=CIRCLE('',#912,1.6); +#332=CIRCLE('',#913,1.6); +#333=CIRCLE('',#915,1.6); +#334=CIRCLE('',#916,1.6); +#335=CIRCLE('',#918,1.6); +#336=CIRCLE('',#919,1.6); +#337=CIRCLE('',#921,1.6); +#338=CIRCLE('',#922,1.6); +#339=CIRCLE('',#924,1.6); +#340=CIRCLE('',#925,1.6); +#341=CIRCLE('',#927,1.6); +#342=CIRCLE('',#928,1.6); +#343=CIRCLE('',#930,1.6); +#344=CIRCLE('',#931,1.6); +#345=CIRCLE('',#933,1.6); +#346=CIRCLE('',#934,1.6); +#347=CIRCLE('',#936,1.6); +#348=CIRCLE('',#937,1.6); +#349=CIRCLE('',#939,1.6); +#350=CIRCLE('',#940,1.6); +#351=CIRCLE('',#942,5.); +#352=CIRCLE('',#943,5.); +#353=CIRCLE('',#945,5.); +#354=CIRCLE('',#946,5.); +#355=CIRCLE('',#948,4.1); +#356=CIRCLE('',#949,4.1); +#357=CIRCLE('',#950,0.1); +#358=CIRCLE('',#951,0.1); +#359=CIRCLE('',#956,17.5); +#360=CIRCLE('',#957,17.5); +#361=CIRCLE('',#959,4.1); +#362=CIRCLE('',#960,0.1); +#363=CIRCLE('',#961,0.1); +#364=CIRCLE('',#962,4.1); +#365=CIRCLE('',#964,17.5); +#366=CIRCLE('',#965,17.5); +#367=CIRCLE('',#968,7.); +#368=CIRCLE('',#969,7.); +#369=CIRCLE('',#971,7.); +#370=CIRCLE('',#972,7.); +#371=VERTEX_POINT('',#1247); +#372=VERTEX_POINT('',#1249); +#373=VERTEX_POINT('',#1253); +#374=VERTEX_POINT('',#1255); +#375=VERTEX_POINT('',#1259); +#376=VERTEX_POINT('',#1261); +#377=VERTEX_POINT('',#1265); +#378=VERTEX_POINT('',#1267); +#379=VERTEX_POINT('',#1271); +#380=VERTEX_POINT('',#1273); +#381=VERTEX_POINT('',#1277); +#382=VERTEX_POINT('',#1279); +#383=VERTEX_POINT('',#1283); +#384=VERTEX_POINT('',#1285); +#385=VERTEX_POINT('',#1289); +#386=VERTEX_POINT('',#1291); +#387=VERTEX_POINT('',#1295); +#388=VERTEX_POINT('',#1297); +#389=VERTEX_POINT('',#1301); +#390=VERTEX_POINT('',#1303); +#391=VERTEX_POINT('',#1307); +#392=VERTEX_POINT('',#1309); +#393=VERTEX_POINT('',#1313); +#394=VERTEX_POINT('',#1315); +#395=VERTEX_POINT('',#1319); +#396=VERTEX_POINT('',#1321); +#397=VERTEX_POINT('',#1325); +#398=VERTEX_POINT('',#1327); +#399=VERTEX_POINT('',#1331); +#400=VERTEX_POINT('',#1333); +#401=VERTEX_POINT('',#1337); +#402=VERTEX_POINT('',#1339); +#403=VERTEX_POINT('',#1343); +#404=VERTEX_POINT('',#1345); +#405=VERTEX_POINT('',#1349); +#406=VERTEX_POINT('',#1351); +#407=VERTEX_POINT('',#1355); +#408=VERTEX_POINT('',#1357); +#409=VERTEX_POINT('',#1361); +#410=VERTEX_POINT('',#1363); +#411=VERTEX_POINT('',#1367); +#412=VERTEX_POINT('',#1368); +#413=VERTEX_POINT('',#1370); +#414=VERTEX_POINT('',#1372); +#415=VERTEX_POINT('',#1376); +#416=VERTEX_POINT('',#1377); +#417=VERTEX_POINT('',#1379); +#418=VERTEX_POINT('',#1381); +#419=VERTEX_POINT('',#1385); +#420=VERTEX_POINT('',#1386); +#421=VERTEX_POINT('',#1388); +#422=VERTEX_POINT('',#1390); +#423=VERTEX_POINT('',#1392); +#424=VERTEX_POINT('',#1394); +#425=VERTEX_POINT('',#1396); +#426=VERTEX_POINT('',#1398); +#427=VERTEX_POINT('',#1402); +#428=VERTEX_POINT('',#1404); +#429=VERTEX_POINT('',#1408); +#430=VERTEX_POINT('',#1410); +#431=VERTEX_POINT('',#1414); +#432=VERTEX_POINT('',#1416); +#433=VERTEX_POINT('',#1423); +#434=VERTEX_POINT('',#1424); +#435=VERTEX_POINT('',#1427); +#436=VERTEX_POINT('',#1429); +#437=VERTEX_POINT('',#1431); +#438=VERTEX_POINT('',#1433); +#439=VERTEX_POINT('',#1436); +#440=VERTEX_POINT('',#1438); +#441=VERTEX_POINT('',#1442); +#442=VERTEX_POINT('',#1444); +#443=VERTEX_POINT('',#1451); +#444=VERTEX_POINT('',#1453); +#445=VERTEX_POINT('',#1457); +#446=VERTEX_POINT('',#1459); +#447=EDGE_CURVE('',#371,#371,#311,.T.); +#448=EDGE_CURVE('',#371,#372,#199,.T.); +#449=EDGE_CURVE('',#372,#372,#312,.T.); +#450=EDGE_CURVE('',#373,#373,#313,.T.); +#451=EDGE_CURVE('',#373,#374,#200,.T.); +#452=EDGE_CURVE('',#374,#374,#314,.T.); +#453=EDGE_CURVE('',#375,#375,#315,.T.); +#454=EDGE_CURVE('',#375,#376,#201,.T.); +#455=EDGE_CURVE('',#376,#376,#316,.T.); +#456=EDGE_CURVE('',#377,#377,#317,.T.); +#457=EDGE_CURVE('',#377,#378,#202,.T.); +#458=EDGE_CURVE('',#378,#378,#318,.T.); +#459=EDGE_CURVE('',#379,#379,#319,.T.); +#460=EDGE_CURVE('',#379,#380,#203,.T.); +#461=EDGE_CURVE('',#380,#380,#320,.T.); +#462=EDGE_CURVE('',#381,#381,#321,.T.); +#463=EDGE_CURVE('',#381,#382,#204,.T.); +#464=EDGE_CURVE('',#382,#382,#322,.T.); +#465=EDGE_CURVE('',#383,#383,#323,.T.); +#466=EDGE_CURVE('',#383,#384,#205,.T.); +#467=EDGE_CURVE('',#384,#384,#324,.T.); +#468=EDGE_CURVE('',#385,#385,#325,.T.); +#469=EDGE_CURVE('',#385,#386,#206,.T.); +#470=EDGE_CURVE('',#386,#386,#326,.T.); +#471=EDGE_CURVE('',#387,#387,#327,.T.); +#472=EDGE_CURVE('',#387,#388,#207,.T.); +#473=EDGE_CURVE('',#388,#388,#328,.T.); +#474=EDGE_CURVE('',#389,#389,#329,.T.); +#475=EDGE_CURVE('',#389,#390,#208,.T.); +#476=EDGE_CURVE('',#390,#390,#330,.T.); +#477=EDGE_CURVE('',#391,#391,#331,.T.); +#478=EDGE_CURVE('',#391,#392,#209,.T.); +#479=EDGE_CURVE('',#392,#392,#332,.T.); +#480=EDGE_CURVE('',#393,#393,#333,.T.); +#481=EDGE_CURVE('',#393,#394,#210,.T.); +#482=EDGE_CURVE('',#394,#394,#334,.T.); +#483=EDGE_CURVE('',#395,#395,#335,.T.); +#484=EDGE_CURVE('',#395,#396,#211,.T.); +#485=EDGE_CURVE('',#396,#396,#336,.T.); +#486=EDGE_CURVE('',#397,#397,#337,.T.); +#487=EDGE_CURVE('',#397,#398,#212,.T.); +#488=EDGE_CURVE('',#398,#398,#338,.T.); +#489=EDGE_CURVE('',#399,#399,#339,.T.); +#490=EDGE_CURVE('',#399,#400,#213,.T.); +#491=EDGE_CURVE('',#400,#400,#340,.T.); +#492=EDGE_CURVE('',#401,#401,#341,.T.); +#493=EDGE_CURVE('',#401,#402,#214,.T.); +#494=EDGE_CURVE('',#402,#402,#342,.T.); +#495=EDGE_CURVE('',#403,#403,#343,.T.); +#496=EDGE_CURVE('',#403,#404,#215,.T.); +#497=EDGE_CURVE('',#404,#404,#344,.T.); +#498=EDGE_CURVE('',#405,#405,#345,.T.); +#499=EDGE_CURVE('',#405,#406,#216,.T.); +#500=EDGE_CURVE('',#406,#406,#346,.T.); +#501=EDGE_CURVE('',#407,#407,#347,.T.); +#502=EDGE_CURVE('',#407,#408,#217,.T.); +#503=EDGE_CURVE('',#408,#408,#348,.T.); +#504=EDGE_CURVE('',#409,#409,#349,.T.); +#505=EDGE_CURVE('',#409,#410,#218,.T.); +#506=EDGE_CURVE('',#410,#410,#350,.T.); +#507=EDGE_CURVE('',#411,#412,#351,.T.); +#508=EDGE_CURVE('',#413,#411,#219,.T.); +#509=EDGE_CURVE('',#414,#413,#352,.T.); +#510=EDGE_CURVE('',#414,#412,#220,.T.); +#511=EDGE_CURVE('',#415,#416,#353,.T.); +#512=EDGE_CURVE('',#417,#415,#221,.T.); +#513=EDGE_CURVE('',#418,#417,#354,.T.); +#514=EDGE_CURVE('',#418,#416,#222,.T.); +#515=EDGE_CURVE('',#419,#420,#355,.T.); +#516=EDGE_CURVE('',#421,#419,#223,.T.); +#517=EDGE_CURVE('',#422,#421,#356,.T.); +#518=EDGE_CURVE('',#423,#422,#224,.T.); +#519=EDGE_CURVE('',#424,#423,#357,.T.); +#520=EDGE_CURVE('',#425,#424,#225,.T.); +#521=EDGE_CURVE('',#426,#425,#358,.T.); +#522=EDGE_CURVE('',#420,#426,#226,.T.); +#523=EDGE_CURVE('',#412,#427,#227,.T.); +#524=EDGE_CURVE('',#428,#414,#228,.T.); +#525=EDGE_CURVE('',#428,#427,#229,.T.); +#526=EDGE_CURVE('',#416,#429,#230,.T.); +#527=EDGE_CURVE('',#430,#418,#231,.T.); +#528=EDGE_CURVE('',#430,#429,#232,.T.); +#529=EDGE_CURVE('',#431,#422,#233,.T.); +#530=EDGE_CURVE('',#432,#431,#234,.T.); +#531=EDGE_CURVE('',#423,#432,#235,.T.); +#532=EDGE_CURVE('',#427,#431,#359,.T.); +#533=EDGE_CURVE('',#432,#428,#360,.T.); +#534=EDGE_CURVE('',#433,#434,#361,.T.); +#535=EDGE_CURVE('',#417,#433,#236,.T.); +#536=EDGE_CURVE('',#435,#415,#237,.T.); +#537=EDGE_CURVE('',#436,#435,#362,.T.); +#538=EDGE_CURVE('',#437,#436,#238,.T.); +#539=EDGE_CURVE('',#438,#437,#363,.T.); +#540=EDGE_CURVE('',#413,#438,#239,.T.); +#541=EDGE_CURVE('',#439,#411,#240,.T.); +#542=EDGE_CURVE('',#440,#439,#364,.T.); +#543=EDGE_CURVE('',#434,#440,#241,.T.); +#544=EDGE_CURVE('',#429,#441,#365,.T.); +#545=EDGE_CURVE('',#442,#430,#366,.T.); +#546=EDGE_CURVE('',#442,#441,#242,.T.); +#547=EDGE_CURVE('',#441,#426,#243,.T.); +#548=EDGE_CURVE('',#420,#442,#244,.T.); +#549=EDGE_CURVE('',#443,#443,#367,.T.); +#550=EDGE_CURVE('',#443,#444,#245,.T.); +#551=EDGE_CURVE('',#444,#444,#368,.T.); +#552=EDGE_CURVE('',#445,#445,#369,.T.); +#553=EDGE_CURVE('',#445,#446,#246,.T.); +#554=EDGE_CURVE('',#446,#446,#370,.T.); +#555=EDGE_CURVE('',#421,#440,#247,.T.); +#556=EDGE_CURVE('',#434,#419,#248,.T.); +#557=EDGE_CURVE('',#426,#435,#249,.T.); +#558=EDGE_CURVE('',#436,#425,#250,.T.); +#559=EDGE_CURVE('',#439,#422,#251,.T.); +#560=EDGE_CURVE('',#420,#433,#252,.T.); +#561=EDGE_CURVE('',#424,#437,#253,.T.); +#562=EDGE_CURVE('',#438,#423,#254,.T.); +#563=ORIENTED_EDGE('',*,*,#447,.F.); +#564=ORIENTED_EDGE('',*,*,#448,.T.); +#565=ORIENTED_EDGE('',*,*,#449,.F.); +#566=ORIENTED_EDGE('',*,*,#448,.F.); +#567=ORIENTED_EDGE('',*,*,#450,.F.); +#568=ORIENTED_EDGE('',*,*,#451,.T.); +#569=ORIENTED_EDGE('',*,*,#452,.F.); +#570=ORIENTED_EDGE('',*,*,#451,.F.); +#571=ORIENTED_EDGE('',*,*,#453,.F.); +#572=ORIENTED_EDGE('',*,*,#454,.T.); +#573=ORIENTED_EDGE('',*,*,#455,.F.); +#574=ORIENTED_EDGE('',*,*,#454,.F.); +#575=ORIENTED_EDGE('',*,*,#456,.F.); +#576=ORIENTED_EDGE('',*,*,#457,.T.); +#577=ORIENTED_EDGE('',*,*,#458,.F.); +#578=ORIENTED_EDGE('',*,*,#457,.F.); +#579=ORIENTED_EDGE('',*,*,#459,.F.); +#580=ORIENTED_EDGE('',*,*,#460,.T.); +#581=ORIENTED_EDGE('',*,*,#461,.F.); +#582=ORIENTED_EDGE('',*,*,#460,.F.); +#583=ORIENTED_EDGE('',*,*,#462,.F.); +#584=ORIENTED_EDGE('',*,*,#463,.T.); +#585=ORIENTED_EDGE('',*,*,#464,.F.); +#586=ORIENTED_EDGE('',*,*,#463,.F.); +#587=ORIENTED_EDGE('',*,*,#465,.F.); +#588=ORIENTED_EDGE('',*,*,#466,.T.); +#589=ORIENTED_EDGE('',*,*,#467,.F.); +#590=ORIENTED_EDGE('',*,*,#466,.F.); +#591=ORIENTED_EDGE('',*,*,#468,.F.); +#592=ORIENTED_EDGE('',*,*,#469,.T.); +#593=ORIENTED_EDGE('',*,*,#470,.F.); +#594=ORIENTED_EDGE('',*,*,#469,.F.); +#595=ORIENTED_EDGE('',*,*,#471,.F.); +#596=ORIENTED_EDGE('',*,*,#472,.T.); +#597=ORIENTED_EDGE('',*,*,#473,.F.); +#598=ORIENTED_EDGE('',*,*,#472,.F.); +#599=ORIENTED_EDGE('',*,*,#474,.F.); +#600=ORIENTED_EDGE('',*,*,#475,.T.); +#601=ORIENTED_EDGE('',*,*,#476,.F.); +#602=ORIENTED_EDGE('',*,*,#475,.F.); +#603=ORIENTED_EDGE('',*,*,#477,.F.); +#604=ORIENTED_EDGE('',*,*,#478,.T.); +#605=ORIENTED_EDGE('',*,*,#479,.F.); +#606=ORIENTED_EDGE('',*,*,#478,.F.); +#607=ORIENTED_EDGE('',*,*,#480,.F.); +#608=ORIENTED_EDGE('',*,*,#481,.T.); +#609=ORIENTED_EDGE('',*,*,#482,.F.); +#610=ORIENTED_EDGE('',*,*,#481,.F.); +#611=ORIENTED_EDGE('',*,*,#483,.F.); +#612=ORIENTED_EDGE('',*,*,#484,.T.); +#613=ORIENTED_EDGE('',*,*,#485,.F.); +#614=ORIENTED_EDGE('',*,*,#484,.F.); +#615=ORIENTED_EDGE('',*,*,#486,.F.); +#616=ORIENTED_EDGE('',*,*,#487,.T.); +#617=ORIENTED_EDGE('',*,*,#488,.F.); +#618=ORIENTED_EDGE('',*,*,#487,.F.); +#619=ORIENTED_EDGE('',*,*,#489,.F.); +#620=ORIENTED_EDGE('',*,*,#490,.T.); +#621=ORIENTED_EDGE('',*,*,#491,.F.); +#622=ORIENTED_EDGE('',*,*,#490,.F.); +#623=ORIENTED_EDGE('',*,*,#492,.F.); +#624=ORIENTED_EDGE('',*,*,#493,.T.); +#625=ORIENTED_EDGE('',*,*,#494,.F.); +#626=ORIENTED_EDGE('',*,*,#493,.F.); +#627=ORIENTED_EDGE('',*,*,#495,.F.); +#628=ORIENTED_EDGE('',*,*,#496,.T.); +#629=ORIENTED_EDGE('',*,*,#497,.F.); +#630=ORIENTED_EDGE('',*,*,#496,.F.); +#631=ORIENTED_EDGE('',*,*,#498,.F.); +#632=ORIENTED_EDGE('',*,*,#499,.T.); +#633=ORIENTED_EDGE('',*,*,#500,.F.); +#634=ORIENTED_EDGE('',*,*,#499,.F.); +#635=ORIENTED_EDGE('',*,*,#501,.F.); +#636=ORIENTED_EDGE('',*,*,#502,.T.); +#637=ORIENTED_EDGE('',*,*,#503,.F.); +#638=ORIENTED_EDGE('',*,*,#502,.F.); +#639=ORIENTED_EDGE('',*,*,#504,.F.); +#640=ORIENTED_EDGE('',*,*,#505,.T.); +#641=ORIENTED_EDGE('',*,*,#506,.F.); +#642=ORIENTED_EDGE('',*,*,#505,.F.); +#643=ORIENTED_EDGE('',*,*,#507,.F.); +#644=ORIENTED_EDGE('',*,*,#508,.F.); +#645=ORIENTED_EDGE('',*,*,#509,.F.); +#646=ORIENTED_EDGE('',*,*,#510,.T.); +#647=ORIENTED_EDGE('',*,*,#511,.F.); +#648=ORIENTED_EDGE('',*,*,#512,.F.); +#649=ORIENTED_EDGE('',*,*,#513,.F.); +#650=ORIENTED_EDGE('',*,*,#514,.T.); +#651=ORIENTED_EDGE('',*,*,#515,.F.); +#652=ORIENTED_EDGE('',*,*,#516,.F.); +#653=ORIENTED_EDGE('',*,*,#517,.F.); +#654=ORIENTED_EDGE('',*,*,#518,.F.); +#655=ORIENTED_EDGE('',*,*,#519,.F.); +#656=ORIENTED_EDGE('',*,*,#520,.F.); +#657=ORIENTED_EDGE('',*,*,#521,.F.); +#658=ORIENTED_EDGE('',*,*,#522,.F.); +#659=ORIENTED_EDGE('',*,*,#523,.F.); +#660=ORIENTED_EDGE('',*,*,#510,.F.); +#661=ORIENTED_EDGE('',*,*,#524,.F.); +#662=ORIENTED_EDGE('',*,*,#525,.T.); +#663=ORIENTED_EDGE('',*,*,#526,.F.); +#664=ORIENTED_EDGE('',*,*,#514,.F.); +#665=ORIENTED_EDGE('',*,*,#527,.F.); +#666=ORIENTED_EDGE('',*,*,#528,.T.); +#667=ORIENTED_EDGE('',*,*,#529,.F.); +#668=ORIENTED_EDGE('',*,*,#530,.F.); +#669=ORIENTED_EDGE('',*,*,#531,.F.); +#670=ORIENTED_EDGE('',*,*,#518,.T.); +#671=ORIENTED_EDGE('',*,*,#532,.F.); +#672=ORIENTED_EDGE('',*,*,#525,.F.); +#673=ORIENTED_EDGE('',*,*,#533,.F.); +#674=ORIENTED_EDGE('',*,*,#530,.T.); +#675=ORIENTED_EDGE('',*,*,#534,.F.); +#676=ORIENTED_EDGE('',*,*,#535,.F.); +#677=ORIENTED_EDGE('',*,*,#512,.T.); +#678=ORIENTED_EDGE('',*,*,#536,.F.); +#679=ORIENTED_EDGE('',*,*,#537,.F.); +#680=ORIENTED_EDGE('',*,*,#538,.F.); +#681=ORIENTED_EDGE('',*,*,#539,.F.); +#682=ORIENTED_EDGE('',*,*,#540,.F.); +#683=ORIENTED_EDGE('',*,*,#508,.T.); +#684=ORIENTED_EDGE('',*,*,#541,.F.); +#685=ORIENTED_EDGE('',*,*,#542,.F.); +#686=ORIENTED_EDGE('',*,*,#543,.F.); +#687=ORIENTED_EDGE('',*,*,#544,.F.); +#688=ORIENTED_EDGE('',*,*,#528,.F.); +#689=ORIENTED_EDGE('',*,*,#545,.F.); +#690=ORIENTED_EDGE('',*,*,#546,.T.); +#691=ORIENTED_EDGE('',*,*,#547,.F.); +#692=ORIENTED_EDGE('',*,*,#546,.F.); +#693=ORIENTED_EDGE('',*,*,#548,.F.); +#694=ORIENTED_EDGE('',*,*,#522,.T.); +#695=ORIENTED_EDGE('',*,*,#549,.F.); +#696=ORIENTED_EDGE('',*,*,#550,.T.); +#697=ORIENTED_EDGE('',*,*,#551,.F.); +#698=ORIENTED_EDGE('',*,*,#550,.F.); +#699=ORIENTED_EDGE('',*,*,#552,.F.); +#700=ORIENTED_EDGE('',*,*,#553,.T.); +#701=ORIENTED_EDGE('',*,*,#554,.F.); +#702=ORIENTED_EDGE('',*,*,#553,.F.); +#703=ORIENTED_EDGE('',*,*,#543,.T.); +#704=ORIENTED_EDGE('',*,*,#555,.F.); +#705=ORIENTED_EDGE('',*,*,#516,.T.); +#706=ORIENTED_EDGE('',*,*,#556,.F.); +#707=ORIENTED_EDGE('',*,*,#449,.T.); +#708=ORIENTED_EDGE('',*,*,#452,.T.); +#709=ORIENTED_EDGE('',*,*,#455,.T.); +#710=ORIENTED_EDGE('',*,*,#458,.T.); +#711=ORIENTED_EDGE('',*,*,#461,.T.); +#712=ORIENTED_EDGE('',*,*,#464,.T.); +#713=ORIENTED_EDGE('',*,*,#467,.T.); +#714=ORIENTED_EDGE('',*,*,#470,.T.); +#715=ORIENTED_EDGE('',*,*,#537,.T.); +#716=ORIENTED_EDGE('',*,*,#557,.F.); +#717=ORIENTED_EDGE('',*,*,#521,.T.); +#718=ORIENTED_EDGE('',*,*,#558,.F.); +#719=ORIENTED_EDGE('',*,*,#541,.T.); +#720=ORIENTED_EDGE('',*,*,#507,.T.); +#721=ORIENTED_EDGE('',*,*,#523,.T.); +#722=ORIENTED_EDGE('',*,*,#532,.T.); +#723=ORIENTED_EDGE('',*,*,#529,.T.); +#724=ORIENTED_EDGE('',*,*,#559,.F.); +#725=ORIENTED_EDGE('',*,*,#473,.T.); +#726=ORIENTED_EDGE('',*,*,#479,.T.); +#727=ORIENTED_EDGE('',*,*,#485,.T.); +#728=ORIENTED_EDGE('',*,*,#491,.T.); +#729=ORIENTED_EDGE('',*,*,#497,.T.); +#730=ORIENTED_EDGE('',*,*,#503,.T.); +#731=ORIENTED_EDGE('',*,*,#554,.T.); +#732=ORIENTED_EDGE('',*,*,#536,.T.); +#733=ORIENTED_EDGE('',*,*,#511,.T.); +#734=ORIENTED_EDGE('',*,*,#526,.T.); +#735=ORIENTED_EDGE('',*,*,#544,.T.); +#736=ORIENTED_EDGE('',*,*,#547,.T.); +#737=ORIENTED_EDGE('',*,*,#557,.T.); +#738=ORIENTED_EDGE('',*,*,#476,.T.); +#739=ORIENTED_EDGE('',*,*,#482,.T.); +#740=ORIENTED_EDGE('',*,*,#488,.T.); +#741=ORIENTED_EDGE('',*,*,#494,.T.); +#742=ORIENTED_EDGE('',*,*,#500,.T.); +#743=ORIENTED_EDGE('',*,*,#506,.T.); +#744=ORIENTED_EDGE('',*,*,#551,.T.); +#745=ORIENTED_EDGE('',*,*,#542,.T.); +#746=ORIENTED_EDGE('',*,*,#559,.T.); +#747=ORIENTED_EDGE('',*,*,#517,.T.); +#748=ORIENTED_EDGE('',*,*,#555,.T.); +#749=ORIENTED_EDGE('',*,*,#534,.T.); +#750=ORIENTED_EDGE('',*,*,#556,.T.); +#751=ORIENTED_EDGE('',*,*,#515,.T.); +#752=ORIENTED_EDGE('',*,*,#560,.T.); +#753=ORIENTED_EDGE('',*,*,#535,.T.); +#754=ORIENTED_EDGE('',*,*,#560,.F.); +#755=ORIENTED_EDGE('',*,*,#548,.T.); +#756=ORIENTED_EDGE('',*,*,#545,.T.); +#757=ORIENTED_EDGE('',*,*,#527,.T.); +#758=ORIENTED_EDGE('',*,*,#513,.T.); +#759=ORIENTED_EDGE('',*,*,#474,.T.); +#760=ORIENTED_EDGE('',*,*,#480,.T.); +#761=ORIENTED_EDGE('',*,*,#486,.T.); +#762=ORIENTED_EDGE('',*,*,#492,.T.); +#763=ORIENTED_EDGE('',*,*,#498,.T.); +#764=ORIENTED_EDGE('',*,*,#504,.T.); +#765=ORIENTED_EDGE('',*,*,#549,.T.); +#766=ORIENTED_EDGE('',*,*,#539,.T.); +#767=ORIENTED_EDGE('',*,*,#561,.F.); +#768=ORIENTED_EDGE('',*,*,#519,.T.); +#769=ORIENTED_EDGE('',*,*,#562,.F.); +#770=ORIENTED_EDGE('',*,*,#538,.T.); +#771=ORIENTED_EDGE('',*,*,#558,.T.); +#772=ORIENTED_EDGE('',*,*,#520,.T.); +#773=ORIENTED_EDGE('',*,*,#561,.T.); +#774=ORIENTED_EDGE('',*,*,#447,.T.); +#775=ORIENTED_EDGE('',*,*,#450,.T.); +#776=ORIENTED_EDGE('',*,*,#453,.T.); +#777=ORIENTED_EDGE('',*,*,#456,.T.); +#778=ORIENTED_EDGE('',*,*,#459,.T.); +#779=ORIENTED_EDGE('',*,*,#462,.T.); +#780=ORIENTED_EDGE('',*,*,#465,.T.); +#781=ORIENTED_EDGE('',*,*,#468,.T.); +#782=ORIENTED_EDGE('',*,*,#540,.T.); +#783=ORIENTED_EDGE('',*,*,#562,.T.); +#784=ORIENTED_EDGE('',*,*,#531,.T.); +#785=ORIENTED_EDGE('',*,*,#533,.T.); +#786=ORIENTED_EDGE('',*,*,#524,.T.); +#787=ORIENTED_EDGE('',*,*,#509,.T.); +#788=ORIENTED_EDGE('',*,*,#471,.T.); +#789=ORIENTED_EDGE('',*,*,#477,.T.); +#790=ORIENTED_EDGE('',*,*,#483,.T.); +#791=ORIENTED_EDGE('',*,*,#489,.T.); +#792=ORIENTED_EDGE('',*,*,#495,.T.); +#793=ORIENTED_EDGE('',*,*,#501,.T.); +#794=ORIENTED_EDGE('',*,*,#552,.T.); +#795=CYLINDRICAL_SURFACE('',#881,1.2645); +#796=CYLINDRICAL_SURFACE('',#884,1.2645); +#797=CYLINDRICAL_SURFACE('',#887,1.6); +#798=CYLINDRICAL_SURFACE('',#890,1.6); +#799=CYLINDRICAL_SURFACE('',#893,1.6); +#800=CYLINDRICAL_SURFACE('',#896,1.6); +#801=CYLINDRICAL_SURFACE('',#899,1.6); +#802=CYLINDRICAL_SURFACE('',#902,1.6); +#803=CYLINDRICAL_SURFACE('',#905,1.6); +#804=CYLINDRICAL_SURFACE('',#908,1.6); +#805=CYLINDRICAL_SURFACE('',#911,1.6); +#806=CYLINDRICAL_SURFACE('',#914,1.6); +#807=CYLINDRICAL_SURFACE('',#917,1.6); +#808=CYLINDRICAL_SURFACE('',#920,1.6); +#809=CYLINDRICAL_SURFACE('',#923,1.6); +#810=CYLINDRICAL_SURFACE('',#926,1.6); +#811=CYLINDRICAL_SURFACE('',#929,1.6); +#812=CYLINDRICAL_SURFACE('',#932,1.6); +#813=CYLINDRICAL_SURFACE('',#935,1.6); +#814=CYLINDRICAL_SURFACE('',#938,1.6); +#815=CYLINDRICAL_SURFACE('',#941,5.); +#816=CYLINDRICAL_SURFACE('',#944,5.); +#817=CYLINDRICAL_SURFACE('',#955,17.5); +#818=CYLINDRICAL_SURFACE('',#963,17.5); +#819=CYLINDRICAL_SURFACE('',#967,7.); +#820=CYLINDRICAL_SURFACE('',#970,7.); +#821=CYLINDRICAL_SURFACE('',#974,0.1); +#822=CYLINDRICAL_SURFACE('',#977,4.1); +#823=CYLINDRICAL_SURFACE('',#978,4.1); +#824=CYLINDRICAL_SURFACE('',#980,0.1); +#825=ADVANCED_FACE('',(#71),#795,.F.); +#826=ADVANCED_FACE('',(#72),#796,.F.); +#827=ADVANCED_FACE('',(#73),#797,.F.); +#828=ADVANCED_FACE('',(#74),#798,.F.); +#829=ADVANCED_FACE('',(#75),#799,.F.); +#830=ADVANCED_FACE('',(#76),#800,.F.); +#831=ADVANCED_FACE('',(#77),#801,.F.); +#832=ADVANCED_FACE('',(#78),#802,.F.); +#833=ADVANCED_FACE('',(#79),#803,.F.); +#834=ADVANCED_FACE('',(#80),#804,.F.); +#835=ADVANCED_FACE('',(#81),#805,.F.); +#836=ADVANCED_FACE('',(#82),#806,.F.); +#837=ADVANCED_FACE('',(#83),#807,.F.); +#838=ADVANCED_FACE('',(#84),#808,.F.); +#839=ADVANCED_FACE('',(#85),#809,.F.); +#840=ADVANCED_FACE('',(#86),#810,.F.); +#841=ADVANCED_FACE('',(#87),#811,.F.); +#842=ADVANCED_FACE('',(#88),#812,.F.); +#843=ADVANCED_FACE('',(#89),#813,.F.); +#844=ADVANCED_FACE('',(#90),#814,.F.); +#845=ADVANCED_FACE('',(#91),#815,.T.); +#846=ADVANCED_FACE('',(#92),#816,.T.); +#847=ADVANCED_FACE('',(#93),#59,.F.); +#848=ADVANCED_FACE('',(#94),#60,.F.); +#849=ADVANCED_FACE('',(#95),#61,.F.); +#850=ADVANCED_FACE('',(#96),#62,.F.); +#851=ADVANCED_FACE('',(#97),#817,.T.); +#852=ADVANCED_FACE('',(#98),#63,.F.); +#853=ADVANCED_FACE('',(#99),#818,.T.); +#854=ADVANCED_FACE('',(#100),#64,.F.); +#855=ADVANCED_FACE('',(#101),#819,.F.); +#856=ADVANCED_FACE('',(#102),#820,.F.); +#857=ADVANCED_FACE('',(#103,#15,#16,#17,#18,#19,#20,#21,#22),#65,.T.); +#858=ADVANCED_FACE('',(#104),#821,.F.); +#859=ADVANCED_FACE('',(#105,#23,#24,#25,#26,#27,#28,#29),#66,.T.); +#860=ADVANCED_FACE('',(#106,#30,#31,#32,#33,#34,#35,#36),#67,.F.); +#861=ADVANCED_FACE('',(#107),#822,.T.); +#862=ADVANCED_FACE('',(#108),#823,.T.); +#863=ADVANCED_FACE('',(#109,#37,#38,#39,#40,#41,#42,#43),#68,.T.); +#864=ADVANCED_FACE('',(#110),#824,.F.); +#865=ADVANCED_FACE('',(#111,#44,#45,#46,#47,#48,#49,#50,#51),#69,.F.); +#866=ADVANCED_FACE('',(#112,#52,#53,#54,#55,#56,#57,#58),#70,.F.); +#867=CLOSED_SHELL('',(#825,#826,#827,#828,#829,#830,#831,#832,#833,#834, +#835,#836,#837,#838,#839,#840,#841,#842,#843,#844,#845,#846,#847,#848,#849, +#850,#851,#852,#853,#854,#855,#856,#857,#858,#859,#860,#861,#862,#863,#864, +#865,#866)); +#868=DERIVED_UNIT_ELEMENT(#870,1.); +#869=DERIVED_UNIT_ELEMENT(#1485,-3.); +#870=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT(.KILO.,.GRAM.) +); +#871=DERIVED_UNIT((#868,#869)); +#872=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(7850.),#871); +#873=PROPERTY_DEFINITION_REPRESENTATION(#878,#875); +#874=PROPERTY_DEFINITION_REPRESENTATION(#879,#876); +#875=REPRESENTATION('material name',(#877),#1482); +#876=REPRESENTATION('density',(#872),#1482); +#877=DESCRIPTIVE_REPRESENTATION_ITEM('Steel','Steel'); +#878=PROPERTY_DEFINITION('material property','material name',#1492); +#879=PROPERTY_DEFINITION('material property','density of part',#1492); +#880=AXIS2_PLACEMENT_3D('',#1245,#983,#984); +#881=AXIS2_PLACEMENT_3D('',#1246,#985,#986); +#882=AXIS2_PLACEMENT_3D('',#1248,#987,#988); +#883=AXIS2_PLACEMENT_3D('',#1251,#990,#991); +#884=AXIS2_PLACEMENT_3D('',#1252,#992,#993); +#885=AXIS2_PLACEMENT_3D('',#1254,#994,#995); +#886=AXIS2_PLACEMENT_3D('',#1257,#997,#998); +#887=AXIS2_PLACEMENT_3D('',#1258,#999,#1000); +#888=AXIS2_PLACEMENT_3D('',#1260,#1001,#1002); +#889=AXIS2_PLACEMENT_3D('',#1263,#1004,#1005); +#890=AXIS2_PLACEMENT_3D('',#1264,#1006,#1007); +#891=AXIS2_PLACEMENT_3D('',#1266,#1008,#1009); +#892=AXIS2_PLACEMENT_3D('',#1269,#1011,#1012); +#893=AXIS2_PLACEMENT_3D('',#1270,#1013,#1014); +#894=AXIS2_PLACEMENT_3D('',#1272,#1015,#1016); +#895=AXIS2_PLACEMENT_3D('',#1275,#1018,#1019); +#896=AXIS2_PLACEMENT_3D('',#1276,#1020,#1021); +#897=AXIS2_PLACEMENT_3D('',#1278,#1022,#1023); +#898=AXIS2_PLACEMENT_3D('',#1281,#1025,#1026); +#899=AXIS2_PLACEMENT_3D('',#1282,#1027,#1028); +#900=AXIS2_PLACEMENT_3D('',#1284,#1029,#1030); +#901=AXIS2_PLACEMENT_3D('',#1287,#1032,#1033); +#902=AXIS2_PLACEMENT_3D('',#1288,#1034,#1035); +#903=AXIS2_PLACEMENT_3D('',#1290,#1036,#1037); +#904=AXIS2_PLACEMENT_3D('',#1293,#1039,#1040); +#905=AXIS2_PLACEMENT_3D('',#1294,#1041,#1042); +#906=AXIS2_PLACEMENT_3D('',#1296,#1043,#1044); +#907=AXIS2_PLACEMENT_3D('',#1299,#1046,#1047); +#908=AXIS2_PLACEMENT_3D('',#1300,#1048,#1049); +#909=AXIS2_PLACEMENT_3D('',#1302,#1050,#1051); +#910=AXIS2_PLACEMENT_3D('',#1305,#1053,#1054); +#911=AXIS2_PLACEMENT_3D('',#1306,#1055,#1056); +#912=AXIS2_PLACEMENT_3D('',#1308,#1057,#1058); +#913=AXIS2_PLACEMENT_3D('',#1311,#1060,#1061); +#914=AXIS2_PLACEMENT_3D('',#1312,#1062,#1063); +#915=AXIS2_PLACEMENT_3D('',#1314,#1064,#1065); +#916=AXIS2_PLACEMENT_3D('',#1317,#1067,#1068); +#917=AXIS2_PLACEMENT_3D('',#1318,#1069,#1070); +#918=AXIS2_PLACEMENT_3D('',#1320,#1071,#1072); +#919=AXIS2_PLACEMENT_3D('',#1323,#1074,#1075); +#920=AXIS2_PLACEMENT_3D('',#1324,#1076,#1077); +#921=AXIS2_PLACEMENT_3D('',#1326,#1078,#1079); +#922=AXIS2_PLACEMENT_3D('',#1329,#1081,#1082); +#923=AXIS2_PLACEMENT_3D('',#1330,#1083,#1084); +#924=AXIS2_PLACEMENT_3D('',#1332,#1085,#1086); +#925=AXIS2_PLACEMENT_3D('',#1335,#1088,#1089); +#926=AXIS2_PLACEMENT_3D('',#1336,#1090,#1091); +#927=AXIS2_PLACEMENT_3D('',#1338,#1092,#1093); +#928=AXIS2_PLACEMENT_3D('',#1341,#1095,#1096); +#929=AXIS2_PLACEMENT_3D('',#1342,#1097,#1098); +#930=AXIS2_PLACEMENT_3D('',#1344,#1099,#1100); +#931=AXIS2_PLACEMENT_3D('',#1347,#1102,#1103); +#932=AXIS2_PLACEMENT_3D('',#1348,#1104,#1105); +#933=AXIS2_PLACEMENT_3D('',#1350,#1106,#1107); +#934=AXIS2_PLACEMENT_3D('',#1353,#1109,#1110); +#935=AXIS2_PLACEMENT_3D('',#1354,#1111,#1112); +#936=AXIS2_PLACEMENT_3D('',#1356,#1113,#1114); +#937=AXIS2_PLACEMENT_3D('',#1359,#1116,#1117); +#938=AXIS2_PLACEMENT_3D('',#1360,#1118,#1119); +#939=AXIS2_PLACEMENT_3D('',#1362,#1120,#1121); +#940=AXIS2_PLACEMENT_3D('',#1365,#1123,#1124); +#941=AXIS2_PLACEMENT_3D('',#1366,#1125,#1126); +#942=AXIS2_PLACEMENT_3D('',#1369,#1127,#1128); +#943=AXIS2_PLACEMENT_3D('',#1373,#1130,#1131); +#944=AXIS2_PLACEMENT_3D('',#1375,#1133,#1134); +#945=AXIS2_PLACEMENT_3D('',#1378,#1135,#1136); +#946=AXIS2_PLACEMENT_3D('',#1382,#1138,#1139); +#947=AXIS2_PLACEMENT_3D('',#1384,#1141,#1142); +#948=AXIS2_PLACEMENT_3D('',#1387,#1143,#1144); +#949=AXIS2_PLACEMENT_3D('',#1391,#1146,#1147); +#950=AXIS2_PLACEMENT_3D('',#1395,#1149,#1150); +#951=AXIS2_PLACEMENT_3D('',#1399,#1152,#1153); +#952=AXIS2_PLACEMENT_3D('',#1401,#1155,#1156); +#953=AXIS2_PLACEMENT_3D('',#1407,#1160,#1161); +#954=AXIS2_PLACEMENT_3D('',#1413,#1165,#1166); +#955=AXIS2_PLACEMENT_3D('',#1419,#1170,#1171); +#956=AXIS2_PLACEMENT_3D('',#1420,#1172,#1173); +#957=AXIS2_PLACEMENT_3D('',#1421,#1174,#1175); +#958=AXIS2_PLACEMENT_3D('',#1422,#1176,#1177); +#959=AXIS2_PLACEMENT_3D('',#1425,#1178,#1179); +#960=AXIS2_PLACEMENT_3D('',#1430,#1182,#1183); +#961=AXIS2_PLACEMENT_3D('',#1434,#1185,#1186); +#962=AXIS2_PLACEMENT_3D('',#1439,#1189,#1190); +#963=AXIS2_PLACEMENT_3D('',#1441,#1192,#1193); +#964=AXIS2_PLACEMENT_3D('',#1443,#1194,#1195); +#965=AXIS2_PLACEMENT_3D('',#1445,#1196,#1197); +#966=AXIS2_PLACEMENT_3D('',#1447,#1199,#1200); +#967=AXIS2_PLACEMENT_3D('',#1450,#1203,#1204); +#968=AXIS2_PLACEMENT_3D('',#1452,#1205,#1206); +#969=AXIS2_PLACEMENT_3D('',#1455,#1208,#1209); +#970=AXIS2_PLACEMENT_3D('',#1456,#1210,#1211); +#971=AXIS2_PLACEMENT_3D('',#1458,#1212,#1213); +#972=AXIS2_PLACEMENT_3D('',#1461,#1215,#1216); +#973=AXIS2_PLACEMENT_3D('',#1462,#1217,#1218); +#974=AXIS2_PLACEMENT_3D('',#1465,#1221,#1222); +#975=AXIS2_PLACEMENT_3D('',#1468,#1225,#1226); +#976=AXIS2_PLACEMENT_3D('',#1470,#1228,#1229); +#977=AXIS2_PLACEMENT_3D('',#1471,#1230,#1231); +#978=AXIS2_PLACEMENT_3D('',#1472,#1232,#1233); +#979=AXIS2_PLACEMENT_3D('',#1474,#1235,#1236); +#980=AXIS2_PLACEMENT_3D('',#1475,#1237,#1238); +#981=AXIS2_PLACEMENT_3D('',#1478,#1241,#1242); +#982=AXIS2_PLACEMENT_3D('',#1479,#1243,#1244); +#983=DIRECTION('axis',(0.,0.,1.)); +#984=DIRECTION('refdir',(1.,0.,0.)); +#985=DIRECTION('center_axis',(0.,-1.,0.)); +#986=DIRECTION('ref_axis',(0.,0.,1.)); +#987=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#988=DIRECTION('ref_axis',(0.,0.,1.)); +#989=DIRECTION('',(0.,-1.,0.)); +#990=DIRECTION('center_axis',(-1.26775061141452E-33,1.,0.)); +#991=DIRECTION('ref_axis',(0.,0.,1.)); +#992=DIRECTION('center_axis',(0.,-1.,0.)); +#993=DIRECTION('ref_axis',(0.,0.,1.)); +#994=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#995=DIRECTION('ref_axis',(0.,0.,1.)); +#996=DIRECTION('',(0.,-1.,0.)); +#997=DIRECTION('center_axis',(-1.26775061141452E-33,1.,0.)); +#998=DIRECTION('ref_axis',(0.,0.,1.)); +#999=DIRECTION('center_axis',(0.,-1.,0.)); +#1000=DIRECTION('ref_axis',(0.,0.,1.)); +#1001=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#1002=DIRECTION('ref_axis',(0.,0.,1.)); +#1003=DIRECTION('',(0.,-1.,0.)); +#1004=DIRECTION('center_axis',(-1.26775061141452E-33,1.,0.)); +#1005=DIRECTION('ref_axis',(0.,0.,1.)); +#1006=DIRECTION('center_axis',(0.,-1.,0.)); +#1007=DIRECTION('ref_axis',(0.,0.,1.)); +#1008=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#1009=DIRECTION('ref_axis',(0.,0.,1.)); +#1010=DIRECTION('',(0.,-1.,0.)); +#1011=DIRECTION('center_axis',(-1.26775061141452E-33,1.,0.)); +#1012=DIRECTION('ref_axis',(0.,0.,1.)); +#1013=DIRECTION('center_axis',(0.,-1.,0.)); +#1014=DIRECTION('ref_axis',(0.,0.,1.)); +#1015=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#1016=DIRECTION('ref_axis',(0.,0.,1.)); +#1017=DIRECTION('',(0.,-1.,0.)); +#1018=DIRECTION('center_axis',(-1.26775061141452E-33,1.,0.)); +#1019=DIRECTION('ref_axis',(0.,0.,1.)); +#1020=DIRECTION('center_axis',(0.,-1.,0.)); +#1021=DIRECTION('ref_axis',(0.,0.,1.)); +#1022=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#1023=DIRECTION('ref_axis',(0.,0.,1.)); +#1024=DIRECTION('',(0.,-1.,0.)); +#1025=DIRECTION('center_axis',(-1.26775061141452E-33,1.,0.)); +#1026=DIRECTION('ref_axis',(0.,0.,1.)); +#1027=DIRECTION('center_axis',(0.,-1.,0.)); +#1028=DIRECTION('ref_axis',(0.,0.,1.)); +#1029=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#1030=DIRECTION('ref_axis',(0.,0.,1.)); +#1031=DIRECTION('',(0.,-1.,0.)); +#1032=DIRECTION('center_axis',(-1.26775061141452E-33,1.,0.)); +#1033=DIRECTION('ref_axis',(0.,0.,1.)); +#1034=DIRECTION('center_axis',(0.,-1.,0.)); +#1035=DIRECTION('ref_axis',(0.,0.,1.)); +#1036=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#1037=DIRECTION('ref_axis',(0.,0.,1.)); +#1038=DIRECTION('',(0.,-1.,0.)); +#1039=DIRECTION('center_axis',(-1.26775061141452E-33,1.,0.)); +#1040=DIRECTION('ref_axis',(0.,0.,1.)); +#1041=DIRECTION('center_axis',(-1.,0.,0.)); +#1042=DIRECTION('ref_axis',(0.,1.,0.)); +#1043=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1044=DIRECTION('ref_axis',(0.,1.,0.)); +#1045=DIRECTION('',(-1.,0.,0.)); +#1046=DIRECTION('center_axis',(1.,6.83214169000096E-16,0.)); +#1047=DIRECTION('ref_axis',(0.,1.,0.)); +#1048=DIRECTION('center_axis',(-1.,0.,0.)); +#1049=DIRECTION('ref_axis',(0.,1.,0.)); +#1050=DIRECTION('center_axis',(-1.,0.,0.)); +#1051=DIRECTION('ref_axis',(0.,1.,0.)); +#1052=DIRECTION('',(-1.,0.,0.)); +#1053=DIRECTION('center_axis',(1.,0.,0.)); +#1054=DIRECTION('ref_axis',(0.,1.,0.)); +#1055=DIRECTION('center_axis',(-1.,0.,0.)); +#1056=DIRECTION('ref_axis',(0.,1.,0.)); +#1057=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1058=DIRECTION('ref_axis',(0.,1.,0.)); +#1059=DIRECTION('',(-1.,0.,0.)); +#1060=DIRECTION('center_axis',(1.,6.83214169000096E-16,0.)); +#1061=DIRECTION('ref_axis',(0.,1.,0.)); +#1062=DIRECTION('center_axis',(-1.,0.,0.)); +#1063=DIRECTION('ref_axis',(0.,1.,0.)); +#1064=DIRECTION('center_axis',(-1.,0.,0.)); +#1065=DIRECTION('ref_axis',(0.,1.,0.)); +#1066=DIRECTION('',(-1.,0.,0.)); +#1067=DIRECTION('center_axis',(1.,0.,0.)); +#1068=DIRECTION('ref_axis',(0.,1.,0.)); +#1069=DIRECTION('center_axis',(-1.,0.,0.)); +#1070=DIRECTION('ref_axis',(0.,1.,0.)); +#1071=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1072=DIRECTION('ref_axis',(0.,1.,0.)); +#1073=DIRECTION('',(-1.,0.,0.)); +#1074=DIRECTION('center_axis',(1.,6.83214169000096E-16,0.)); +#1075=DIRECTION('ref_axis',(0.,1.,0.)); +#1076=DIRECTION('center_axis',(-1.,0.,0.)); +#1077=DIRECTION('ref_axis',(0.,1.,0.)); +#1078=DIRECTION('center_axis',(-1.,0.,0.)); +#1079=DIRECTION('ref_axis',(0.,1.,0.)); +#1080=DIRECTION('',(-1.,0.,0.)); +#1081=DIRECTION('center_axis',(1.,0.,0.)); +#1082=DIRECTION('ref_axis',(0.,1.,0.)); +#1083=DIRECTION('center_axis',(-1.,0.,0.)); +#1084=DIRECTION('ref_axis',(0.,1.,0.)); +#1085=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1086=DIRECTION('ref_axis',(0.,1.,0.)); +#1087=DIRECTION('',(-1.,0.,0.)); +#1088=DIRECTION('center_axis',(1.,6.83214169000096E-16,0.)); +#1089=DIRECTION('ref_axis',(0.,1.,0.)); +#1090=DIRECTION('center_axis',(-1.,0.,0.)); +#1091=DIRECTION('ref_axis',(0.,1.,0.)); +#1092=DIRECTION('center_axis',(-1.,0.,0.)); +#1093=DIRECTION('ref_axis',(0.,1.,0.)); +#1094=DIRECTION('',(-1.,0.,0.)); +#1095=DIRECTION('center_axis',(1.,0.,0.)); +#1096=DIRECTION('ref_axis',(0.,1.,0.)); +#1097=DIRECTION('center_axis',(-1.,0.,0.)); +#1098=DIRECTION('ref_axis',(0.,1.,0.)); +#1099=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1100=DIRECTION('ref_axis',(0.,1.,0.)); +#1101=DIRECTION('',(-1.,0.,0.)); +#1102=DIRECTION('center_axis',(1.,6.83214169000096E-16,0.)); +#1103=DIRECTION('ref_axis',(0.,1.,0.)); +#1104=DIRECTION('center_axis',(-1.,0.,0.)); +#1105=DIRECTION('ref_axis',(0.,1.,0.)); +#1106=DIRECTION('center_axis',(-1.,0.,0.)); +#1107=DIRECTION('ref_axis',(0.,1.,0.)); +#1108=DIRECTION('',(-1.,0.,0.)); +#1109=DIRECTION('center_axis',(1.,0.,0.)); +#1110=DIRECTION('ref_axis',(0.,1.,0.)); +#1111=DIRECTION('center_axis',(-1.,0.,0.)); +#1112=DIRECTION('ref_axis',(0.,1.,0.)); +#1113=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1114=DIRECTION('ref_axis',(0.,1.,0.)); +#1115=DIRECTION('',(-1.,0.,0.)); +#1116=DIRECTION('center_axis',(1.,6.83214169000096E-16,0.)); +#1117=DIRECTION('ref_axis',(0.,1.,0.)); +#1118=DIRECTION('center_axis',(-1.,0.,0.)); +#1119=DIRECTION('ref_axis',(0.,1.,0.)); +#1120=DIRECTION('center_axis',(-1.,0.,0.)); +#1121=DIRECTION('ref_axis',(0.,1.,0.)); +#1122=DIRECTION('',(-1.,0.,0.)); +#1123=DIRECTION('center_axis',(1.,0.,0.)); +#1124=DIRECTION('ref_axis',(0.,1.,0.)); +#1125=DIRECTION('center_axis',(-1.,0.,0.)); +#1126=DIRECTION('ref_axis',(0.,0.568508529646724,0.822677367938926)); +#1127=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1128=DIRECTION('ref_axis',(0.,0.568508529646724,0.822677367938926)); +#1129=DIRECTION('',(-1.,0.,0.)); +#1130=DIRECTION('center_axis',(1.,6.83214169000096E-16,0.)); +#1131=DIRECTION('ref_axis',(0.,0.568508529646724,0.822677367938926)); +#1132=DIRECTION('',(-1.,0.,0.)); +#1133=DIRECTION('center_axis',(-1.,0.,0.)); +#1134=DIRECTION('ref_axis',(0.,0.568508529646724,0.822677367938926)); +#1135=DIRECTION('center_axis',(-1.,0.,0.)); +#1136=DIRECTION('ref_axis',(0.,0.568508529646724,0.822677367938926)); +#1137=DIRECTION('',(-1.,0.,0.)); +#1138=DIRECTION('center_axis',(1.,0.,0.)); +#1139=DIRECTION('ref_axis',(0.,0.568508529646724,0.822677367938926)); +#1140=DIRECTION('',(-1.,0.,0.)); +#1141=DIRECTION('center_axis',(0.,0.,1.)); +#1142=DIRECTION('ref_axis',(0.,1.,0.)); +#1143=DIRECTION('center_axis',(0.,0.,1.)); +#1144=DIRECTION('ref_axis',(0.70710678118654,-0.707106781186555,0.)); +#1145=DIRECTION('',(1.,1.26775061141452E-33,0.)); +#1146=DIRECTION('center_axis',(0.,0.,1.)); +#1147=DIRECTION('ref_axis',(-0.707106781186547,-0.707106781186548,0.)); +#1148=DIRECTION('',(-1.,0.,0.)); +#1149=DIRECTION('center_axis',(0.,0.,-1.)); +#1150=DIRECTION('ref_axis',(-0.707106781186547,-0.707106781186548,0.)); +#1151=DIRECTION('',(-1.,-1.26775061141452E-33,0.)); +#1152=DIRECTION('center_axis',(0.,0.,-1.)); +#1153=DIRECTION('ref_axis',(0.70710678118654,-0.707106781186555,0.)); +#1154=DIRECTION('',(-1.,0.,0.)); +#1155=DIRECTION('center_axis',(0.,-0.568508529646724,-0.822677367938926)); +#1156=DIRECTION('ref_axis',(0.,-0.822677367938926,0.568508529646724)); +#1157=DIRECTION('',(-5.6206483429158E-16,0.822677367938926,-0.568508529646724)); +#1158=DIRECTION('',(5.6206483429158E-16,-0.822677367938926,0.568508529646724)); +#1159=DIRECTION('',(-1.,0.,0.)); +#1160=DIRECTION('center_axis',(0.,-0.568508529646724,-0.822677367938926)); +#1161=DIRECTION('ref_axis',(0.,-0.822677367938926,0.568508529646724)); +#1162=DIRECTION('',(0.,0.822677367938926,-0.568508529646724)); +#1163=DIRECTION('',(0.,-0.822677367938926,0.568508529646724)); +#1164=DIRECTION('',(-1.,0.,0.)); +#1165=DIRECTION('center_axis',(0.,0.568508529646724,0.822677367938927)); +#1166=DIRECTION('ref_axis',(0.,0.822677367938927,-0.568508529646724)); +#1167=DIRECTION('',(5.6206483429158E-16,-0.822677367938927,0.568508529646724)); +#1168=DIRECTION('',(-1.,0.,0.)); +#1169=DIRECTION('',(-5.6206483429158E-16,0.822677367938927,-0.568508529646724)); +#1170=DIRECTION('center_axis',(-1.,0.,0.)); +#1171=DIRECTION('ref_axis',(0.,0.,-1.)); +#1172=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1173=DIRECTION('ref_axis',(0.,0.,-1.)); +#1174=DIRECTION('center_axis',(1.,6.83214169000096E-16,0.)); +#1175=DIRECTION('ref_axis',(0.,0.,-1.)); +#1176=DIRECTION('center_axis',(0.,0.,-1.)); +#1177=DIRECTION('ref_axis',(0.,-1.,0.)); +#1178=DIRECTION('center_axis',(0.,0.,-1.)); +#1179=DIRECTION('ref_axis',(0.70710678118654,-0.707106781186555,0.)); +#1180=DIRECTION('',(0.,-1.,0.)); +#1181=DIRECTION('',(0.,1.,0.)); +#1182=DIRECTION('center_axis',(0.,0.,1.)); +#1183=DIRECTION('ref_axis',(0.70710678118654,-0.707106781186555,0.)); +#1184=DIRECTION('',(1.,1.26775061141452E-33,0.)); +#1185=DIRECTION('center_axis',(0.,0.,1.)); +#1186=DIRECTION('ref_axis',(-0.707106781186547,-0.707106781186548,0.)); +#1187=DIRECTION('',(6.83214169000096E-16,-1.,0.)); +#1188=DIRECTION('',(-6.83214169000096E-16,1.,0.)); +#1189=DIRECTION('center_axis',(0.,0.,-1.)); +#1190=DIRECTION('ref_axis',(-0.707106781186547,-0.707106781186548,0.)); +#1191=DIRECTION('',(-1.,-1.26775061141452E-33,0.)); +#1192=DIRECTION('center_axis',(-1.,0.,0.)); +#1193=DIRECTION('ref_axis',(0.,0.,-1.)); +#1194=DIRECTION('center_axis',(-1.,0.,0.)); +#1195=DIRECTION('ref_axis',(0.,0.,-1.)); +#1196=DIRECTION('center_axis',(1.,0.,0.)); +#1197=DIRECTION('ref_axis',(0.,0.,-1.)); +#1198=DIRECTION('',(-1.,0.,0.)); +#1199=DIRECTION('center_axis',(0.,0.568508529646724,0.822677367938927)); +#1200=DIRECTION('ref_axis',(0.,0.822677367938927,-0.568508529646724)); +#1201=DIRECTION('',(0.,-0.822677367938927,0.568508529646724)); +#1202=DIRECTION('',(0.,0.822677367938927,-0.568508529646724)); +#1203=DIRECTION('center_axis',(-1.,0.,0.)); +#1204=DIRECTION('ref_axis',(0.,0.,-1.)); +#1205=DIRECTION('center_axis',(-1.,0.,0.)); +#1206=DIRECTION('ref_axis',(0.,0.,-1.)); +#1207=DIRECTION('',(-1.,0.,0.)); +#1208=DIRECTION('center_axis',(1.,0.,0.)); +#1209=DIRECTION('ref_axis',(0.,0.,-1.)); +#1210=DIRECTION('center_axis',(-1.,0.,0.)); +#1211=DIRECTION('ref_axis',(0.,0.,-1.)); +#1212=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1213=DIRECTION('ref_axis',(0.,0.,-1.)); +#1214=DIRECTION('',(-1.,0.,0.)); +#1215=DIRECTION('center_axis',(1.,6.83214169000096E-16,0.)); +#1216=DIRECTION('ref_axis',(0.,0.,-1.)); +#1217=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#1218=DIRECTION('ref_axis',(1.,1.26775061141452E-33,0.)); +#1219=DIRECTION('',(0.,0.,1.)); +#1220=DIRECTION('',(0.,0.,-1.)); +#1221=DIRECTION('center_axis',(0.,0.,-1.)); +#1222=DIRECTION('ref_axis',(0.70710678118654,-0.707106781186555,0.)); +#1223=DIRECTION('',(0.,0.,1.)); +#1224=DIRECTION('',(0.,0.,-1.)); +#1225=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1226=DIRECTION('ref_axis',(6.83214169000096E-16,-1.,0.)); +#1227=DIRECTION('',(0.,0.,-1.)); +#1228=DIRECTION('center_axis',(1.,0.,0.)); +#1229=DIRECTION('ref_axis',(0.,1.,0.)); +#1230=DIRECTION('center_axis',(0.,0.,-1.)); +#1231=DIRECTION('ref_axis',(-0.707106781186547,-0.707106781186548,0.)); +#1232=DIRECTION('center_axis',(0.,0.,-1.)); +#1233=DIRECTION('ref_axis',(0.70710678118654,-0.707106781186555,0.)); +#1234=DIRECTION('',(0.,0.,1.)); +#1235=DIRECTION('center_axis',(1.,0.,0.)); +#1236=DIRECTION('ref_axis',(0.,1.,0.)); +#1237=DIRECTION('center_axis',(0.,0.,-1.)); +#1238=DIRECTION('ref_axis',(-0.707106781186547,-0.707106781186548,0.)); +#1239=DIRECTION('',(0.,0.,1.)); +#1240=DIRECTION('',(0.,0.,-1.)); +#1241=DIRECTION('center_axis',(1.26775061141452E-33,-1.,0.)); +#1242=DIRECTION('ref_axis',(1.,1.26775061141452E-33,0.)); +#1243=DIRECTION('center_axis',(-1.,-6.83214169000096E-16,0.)); +#1244=DIRECTION('ref_axis',(6.83214169000096E-16,-1.,0.)); +#1245=CARTESIAN_POINT('',(0.,0.,0.)); +#1246=CARTESIAN_POINT('Origin',(-21.55,-2.,10.)); +#1247=CARTESIAN_POINT('',(-21.55,0.,8.7355)); +#1248=CARTESIAN_POINT('Origin',(-21.55,0.,10.)); +#1249=CARTESIAN_POINT('',(-21.55,-4.,8.7355)); +#1250=CARTESIAN_POINT('',(-21.55,-2.,8.7355)); +#1251=CARTESIAN_POINT('Origin',(-21.55,-4.,10.)); +#1252=CARTESIAN_POINT('Origin',(21.55,-2.,10.)); +#1253=CARTESIAN_POINT('',(21.55,0.,8.7355)); +#1254=CARTESIAN_POINT('Origin',(21.55,0.,10.)); +#1255=CARTESIAN_POINT('',(21.55,-4.,8.7355)); +#1256=CARTESIAN_POINT('',(21.55,-2.,8.7355)); +#1257=CARTESIAN_POINT('Origin',(21.55,-4.,10.)); +#1258=CARTESIAN_POINT('Origin',(6.75,-500.,-11.6913429510899)); +#1259=CARTESIAN_POINT('',(6.75,0.,-13.2913429510899)); +#1260=CARTESIAN_POINT('Origin',(6.75,0.,-11.6913429510899)); +#1261=CARTESIAN_POINT('',(6.75,-3.99999999999999,-13.2913429510899)); +#1262=CARTESIAN_POINT('',(6.75,-500.,-13.2913429510899)); +#1263=CARTESIAN_POINT('Origin',(6.75,-3.99999999999999,-11.6913429510899)); +#1264=CARTESIAN_POINT('Origin',(-13.5,-500.,-1.11022302462516E-14)); +#1265=CARTESIAN_POINT('',(-13.5,0.,-1.60000000000001)); +#1266=CARTESIAN_POINT('Origin',(-13.5,0.,-1.11022302462516E-14)); +#1267=CARTESIAN_POINT('',(-13.5,-3.99999999999999,-1.60000000000001)); +#1268=CARTESIAN_POINT('',(-13.5,-500.,-1.60000000000001)); +#1269=CARTESIAN_POINT('Origin',(-13.5,-3.99999999999999,-1.11022302462516E-14)); +#1270=CARTESIAN_POINT('Origin',(6.75,-500.,11.6913429510899)); +#1271=CARTESIAN_POINT('',(6.75,0.,10.0913429510899)); +#1272=CARTESIAN_POINT('Origin',(6.75,0.,11.6913429510899)); +#1273=CARTESIAN_POINT('',(6.75,-3.99999999999999,10.0913429510899)); +#1274=CARTESIAN_POINT('',(6.75,-500.,10.0913429510899)); +#1275=CARTESIAN_POINT('Origin',(6.75,-3.99999999999999,11.6913429510899)); +#1276=CARTESIAN_POINT('Origin',(-6.75,-500.,11.6913429510899)); +#1277=CARTESIAN_POINT('',(-6.75,0.,10.0913429510899)); +#1278=CARTESIAN_POINT('Origin',(-6.75,0.,11.6913429510899)); +#1279=CARTESIAN_POINT('',(-6.75,-3.99999999999999,10.0913429510899)); +#1280=CARTESIAN_POINT('',(-6.75,-500.,10.0913429510899)); +#1281=CARTESIAN_POINT('Origin',(-6.75,-3.99999999999999,11.6913429510899)); +#1282=CARTESIAN_POINT('Origin',(-6.74999999999999,-500.,-11.6913429510899)); +#1283=CARTESIAN_POINT('',(-6.74999999999999,0.,-13.2913429510899)); +#1284=CARTESIAN_POINT('Origin',(-6.74999999999999,0.,-11.6913429510899)); +#1285=CARTESIAN_POINT('',(-6.74999999999999,-3.99999999999999,-13.2913429510899)); +#1286=CARTESIAN_POINT('',(-6.74999999999999,-500.,-13.2913429510899)); +#1287=CARTESIAN_POINT('Origin',(-6.74999999999999,-3.99999999999999,-11.6913429510899)); +#1288=CARTESIAN_POINT('Origin',(13.5,-500.,4.44089209850063E-15)); +#1289=CARTESIAN_POINT('',(13.5,0.,-1.6)); +#1290=CARTESIAN_POINT('Origin',(13.5,0.,4.44089209850063E-15)); +#1291=CARTESIAN_POINT('',(13.5,-3.99999999999999,-1.6)); +#1292=CARTESIAN_POINT('',(13.5,-500.,-1.6)); +#1293=CARTESIAN_POINT('Origin',(13.5,-3.99999999999999,4.44089209850063E-15)); +#1294=CARTESIAN_POINT('Origin',(-459.35,22.8086570489071,-13.2500000000052)); +#1295=CARTESIAN_POINT('',(-36.6500000000001,21.2086570489071,-13.2500000000052)); +#1296=CARTESIAN_POINT('Origin',(-36.6500000000001,22.8086570489071,-13.2500000000052)); +#1297=CARTESIAN_POINT('',(-40.65,21.2086570489071,-13.2500000000052)); +#1298=CARTESIAN_POINT('',(-459.35,21.2086570489071,-13.2500000000052)); +#1299=CARTESIAN_POINT('Origin',(-40.65,22.8086570489071,-13.2500000000052)); +#1300=CARTESIAN_POINT('Origin',(-459.35,22.8086570489071,-13.2500000000052)); +#1301=CARTESIAN_POINT('',(40.65,21.2086570489071,-13.2500000000052)); +#1302=CARTESIAN_POINT('Origin',(40.65,22.8086570489071,-13.2500000000052)); +#1303=CARTESIAN_POINT('',(36.65,21.2086570489071,-13.2500000000052)); +#1304=CARTESIAN_POINT('',(-459.35,21.2086570489071,-13.2500000000052)); +#1305=CARTESIAN_POINT('Origin',(36.65,22.8086570489071,-13.2500000000052)); +#1306=CARTESIAN_POINT('Origin',(-459.35,34.5000000000027,-33.5)); +#1307=CARTESIAN_POINT('',(-36.6500000000001,32.9000000000027,-33.5)); +#1308=CARTESIAN_POINT('Origin',(-36.6500000000001,34.5000000000027,-33.5)); +#1309=CARTESIAN_POINT('',(-40.65,32.9000000000027,-33.5)); +#1310=CARTESIAN_POINT('',(-459.35,32.9000000000027,-33.5)); +#1311=CARTESIAN_POINT('Origin',(-40.65,34.5000000000027,-33.5)); +#1312=CARTESIAN_POINT('Origin',(-459.35,34.5000000000027,-33.5)); +#1313=CARTESIAN_POINT('',(40.65,32.9000000000027,-33.5)); +#1314=CARTESIAN_POINT('Origin',(40.65,34.5000000000027,-33.5)); +#1315=CARTESIAN_POINT('',(36.65,32.9000000000027,-33.5)); +#1316=CARTESIAN_POINT('',(-459.35,32.9000000000027,-33.5)); +#1317=CARTESIAN_POINT('Origin',(36.65,34.5000000000027,-33.5)); +#1318=CARTESIAN_POINT('Origin',(-459.35,46.1913429510869,-13.2499999999948)); +#1319=CARTESIAN_POINT('',(-36.6500000000001,44.5913429510869,-13.2499999999948)); +#1320=CARTESIAN_POINT('Origin',(-36.6500000000001,46.1913429510869,-13.2499999999948)); +#1321=CARTESIAN_POINT('',(-40.65,44.5913429510869,-13.2499999999948)); +#1322=CARTESIAN_POINT('',(-459.35,44.5913429510869,-13.2499999999948)); +#1323=CARTESIAN_POINT('Origin',(-40.65,46.1913429510869,-13.2499999999948)); +#1324=CARTESIAN_POINT('Origin',(-459.35,46.1913429510869,-13.2499999999948)); +#1325=CARTESIAN_POINT('',(40.65,44.5913429510869,-13.2499999999948)); +#1326=CARTESIAN_POINT('Origin',(40.65,46.1913429510869,-13.2499999999948)); +#1327=CARTESIAN_POINT('',(36.65,44.5913429510869,-13.2499999999948)); +#1328=CARTESIAN_POINT('',(-459.35,44.5913429510869,-13.2499999999948)); +#1329=CARTESIAN_POINT('Origin',(36.65,46.1913429510869,-13.2499999999948)); +#1330=CARTESIAN_POINT('Origin',(-459.35,46.1913429510929,-26.7499999999948)); +#1331=CARTESIAN_POINT('',(-36.6500000000001,44.5913429510929,-26.7499999999948)); +#1332=CARTESIAN_POINT('Origin',(-36.6500000000001,46.1913429510929,-26.7499999999948)); +#1333=CARTESIAN_POINT('',(-40.65,44.5913429510929,-26.7499999999948)); +#1334=CARTESIAN_POINT('',(-459.35,44.5913429510929,-26.7499999999948)); +#1335=CARTESIAN_POINT('Origin',(-40.65,46.1913429510929,-26.7499999999948)); +#1336=CARTESIAN_POINT('Origin',(-459.35,46.1913429510929,-26.7499999999948)); +#1337=CARTESIAN_POINT('',(40.65,44.5913429510929,-26.7499999999948)); +#1338=CARTESIAN_POINT('Origin',(40.65,46.1913429510929,-26.7499999999948)); +#1339=CARTESIAN_POINT('',(36.65,44.5913429510929,-26.7499999999948)); +#1340=CARTESIAN_POINT('',(-459.35,44.5913429510929,-26.7499999999948)); +#1341=CARTESIAN_POINT('Origin',(36.65,46.1913429510929,-26.7499999999948)); +#1342=CARTESIAN_POINT('Origin',(-459.35,22.8086570489131,-26.7500000000052)); +#1343=CARTESIAN_POINT('',(-36.6500000000001,21.2086570489131,-26.7500000000052)); +#1344=CARTESIAN_POINT('Origin',(-36.6500000000001,22.8086570489131,-26.7500000000052)); +#1345=CARTESIAN_POINT('',(-40.65,21.2086570489131,-26.7500000000052)); +#1346=CARTESIAN_POINT('',(-459.35,21.2086570489131,-26.7500000000052)); +#1347=CARTESIAN_POINT('Origin',(-40.65,22.8086570489131,-26.7500000000052)); +#1348=CARTESIAN_POINT('Origin',(-459.35,22.8086570489131,-26.7500000000052)); +#1349=CARTESIAN_POINT('',(40.65,21.2086570489131,-26.7500000000052)); +#1350=CARTESIAN_POINT('Origin',(40.65,22.8086570489131,-26.7500000000052)); +#1351=CARTESIAN_POINT('',(36.65,21.2086570489131,-26.7500000000052)); +#1352=CARTESIAN_POINT('',(-459.35,21.2086570489131,-26.7500000000052)); +#1353=CARTESIAN_POINT('Origin',(36.65,22.8086570489131,-26.7500000000052)); +#1354=CARTESIAN_POINT('Origin',(-459.35,34.499999999994,-6.49999999999999)); +#1355=CARTESIAN_POINT('',(-36.6500000000001,32.899999999994,-6.49999999999999)); +#1356=CARTESIAN_POINT('Origin',(-36.6500000000001,34.499999999994,-6.49999999999999)); +#1357=CARTESIAN_POINT('',(-40.65,32.899999999994,-6.49999999999999)); +#1358=CARTESIAN_POINT('',(-459.35,32.899999999994,-6.49999999999999)); +#1359=CARTESIAN_POINT('Origin',(-40.65,34.499999999994,-6.49999999999999)); +#1360=CARTESIAN_POINT('Origin',(-459.35,34.499999999994,-6.49999999999999)); +#1361=CARTESIAN_POINT('',(40.65,32.899999999994,-6.49999999999999)); +#1362=CARTESIAN_POINT('Origin',(40.65,34.499999999994,-6.49999999999999)); +#1363=CARTESIAN_POINT('',(36.65,32.899999999994,-6.49999999999999)); +#1364=CARTESIAN_POINT('',(-459.35,32.899999999994,-6.49999999999999)); +#1365=CARTESIAN_POINT('Origin',(36.65,34.499999999994,-6.49999999999999)); +#1366=CARTESIAN_POINT('Origin',(40.65,9.45725443756826,12.5)); +#1367=CARTESIAN_POINT('',(-40.65,9.45725443756826,17.5)); +#1368=CARTESIAN_POINT('',(-40.65,12.2997970858019,16.6133868396946)); +#1369=CARTESIAN_POINT('Origin',(-40.65,9.45725443756826,12.5)); +#1370=CARTESIAN_POINT('',(-36.65,9.45725443756826,17.5)); +#1371=CARTESIAN_POINT('',(40.65,9.45725443756826,17.5)); +#1372=CARTESIAN_POINT('',(-36.65,12.2997970858019,16.6133868396946)); +#1373=CARTESIAN_POINT('Origin',(-36.65,9.45725443756826,12.5)); +#1374=CARTESIAN_POINT('',(40.65,12.2997970858019,16.6133868396946)); +#1375=CARTESIAN_POINT('Origin',(40.65,9.45725443756826,12.5)); +#1376=CARTESIAN_POINT('',(36.65,9.45725443756826,17.5)); +#1377=CARTESIAN_POINT('',(36.65,12.2997970858019,16.6133868396946)); +#1378=CARTESIAN_POINT('Origin',(36.65,9.45725443756826,12.5)); +#1379=CARTESIAN_POINT('',(40.65,9.45725443756826,17.5)); +#1380=CARTESIAN_POINT('',(40.65,9.45725443756826,17.5)); +#1381=CARTESIAN_POINT('',(40.65,12.2997970858019,16.6133868396946)); +#1382=CARTESIAN_POINT('Origin',(40.65,9.45725443756826,12.5)); +#1383=CARTESIAN_POINT('',(40.65,12.2997970858019,16.6133868396946)); +#1384=CARTESIAN_POINT('Origin',(40.65,-4.,-17.5)); +#1385=CARTESIAN_POINT('',(36.55,-4.,-17.5)); +#1386=CARTESIAN_POINT('',(40.65,0.1,-17.5)); +#1387=CARTESIAN_POINT('Origin',(36.55,0.1,-17.5)); +#1388=CARTESIAN_POINT('',(-36.55,-4.,-17.5)); +#1389=CARTESIAN_POINT('',(2.,-4.,-17.5)); +#1390=CARTESIAN_POINT('',(-40.65,0.1,-17.5)); +#1391=CARTESIAN_POINT('Origin',(-36.55,0.0999999999999979,-17.5)); +#1392=CARTESIAN_POINT('',(-36.65,0.1,-17.5)); +#1393=CARTESIAN_POINT('',(40.65,0.1,-17.5)); +#1394=CARTESIAN_POINT('',(-36.55,0.,-17.5)); +#1395=CARTESIAN_POINT('Origin',(-36.55,0.0999999999999979,-17.5)); +#1396=CARTESIAN_POINT('',(36.55,0.,-17.5)); +#1397=CARTESIAN_POINT('',(2.,0.,-17.5)); +#1398=CARTESIAN_POINT('',(36.65,0.1,-17.5)); +#1399=CARTESIAN_POINT('Origin',(36.55,0.1,-17.5)); +#1400=CARTESIAN_POINT('',(40.65,0.1,-17.5)); +#1401=CARTESIAN_POINT('Origin',(40.65,44.4488992688177,-5.60314606106879)); +#1402=CARTESIAN_POINT('',(-40.65,44.4488992688177,-5.60314606106879)); +#1403=CARTESIAN_POINT('',(-40.65,45.6938912131522,-6.46349371043818)); +#1404=CARTESIAN_POINT('',(-36.65,44.4488992688177,-5.60314606106879)); +#1405=CARTESIAN_POINT('',(-36.65,45.6938912131522,-6.46349371043819)); +#1406=CARTESIAN_POINT('',(40.65,44.4488992688177,-5.60314606106879)); +#1407=CARTESIAN_POINT('Origin',(40.65,44.4488992688177,-5.60314606106879)); +#1408=CARTESIAN_POINT('',(36.65,44.4488992688177,-5.60314606106879)); +#1409=CARTESIAN_POINT('',(36.65,28.0971418684604,5.6966829108973)); +#1410=CARTESIAN_POINT('',(40.65,44.4488992688177,-5.60314606106879)); +#1411=CARTESIAN_POINT('',(40.65,28.0971418684604,5.6966829108973)); +#1412=CARTESIAN_POINT('',(40.65,44.4488992688177,-5.60314606106879)); +#1413=CARTESIAN_POINT('Origin',(40.65,0.100000000000002,-17.5)); +#1414=CARTESIAN_POINT('',(-40.65,24.5511007311823,-34.3968539389312)); +#1415=CARTESIAN_POINT('',(-40.65,13.5705423099257,-26.808774618835)); +#1416=CARTESIAN_POINT('',(-36.65,24.5511007311823,-34.3968539389312)); +#1417=CARTESIAN_POINT('',(40.65,24.5511007311823,-34.3968539389312)); +#1418=CARTESIAN_POINT('',(-36.65,13.5705423099257,-26.808774618835)); +#1419=CARTESIAN_POINT('Origin',(40.65,34.5,-20.)); +#1420=CARTESIAN_POINT('Origin',(-40.65,34.5,-20.)); +#1421=CARTESIAN_POINT('Origin',(-36.65,34.5,-20.)); +#1422=CARTESIAN_POINT('Origin',(40.65,9.45725443756826,17.5)); +#1423=CARTESIAN_POINT('',(40.65,0.1,17.5)); +#1424=CARTESIAN_POINT('',(36.55,-4.00000005960464,17.5)); +#1425=CARTESIAN_POINT('Origin',(36.55,0.1,17.5)); +#1426=CARTESIAN_POINT('',(40.65,4.72862721878413,17.5)); +#1427=CARTESIAN_POINT('',(36.65,0.1,17.5)); +#1428=CARTESIAN_POINT('',(36.65,4.72862721878413,17.5)); +#1429=CARTESIAN_POINT('',(36.55,0.,17.5)); +#1430=CARTESIAN_POINT('Origin',(36.55,0.1,17.5)); +#1431=CARTESIAN_POINT('',(-36.55,0.,17.5)); +#1432=CARTESIAN_POINT('',(2.,0.,17.5)); +#1433=CARTESIAN_POINT('',(-36.65,0.0999999999999978,17.5)); +#1434=CARTESIAN_POINT('Origin',(-36.55,0.0999999999999979,17.5)); +#1435=CARTESIAN_POINT('',(-36.65,30.7286272187841,17.5)); +#1436=CARTESIAN_POINT('',(-40.65,0.0999999999999951,17.5)); +#1437=CARTESIAN_POINT('',(-40.65,30.7286272187841,17.5)); +#1438=CARTESIAN_POINT('',(-36.55,-4.00000005960464,17.5)); +#1439=CARTESIAN_POINT('Origin',(-36.55,0.0999999999999979,17.5)); +#1440=CARTESIAN_POINT('',(2.,-4.,17.5)); +#1441=CARTESIAN_POINT('Origin',(40.65,34.5,-20.)); +#1442=CARTESIAN_POINT('',(36.65,24.5511007311823,-34.3968539389312)); +#1443=CARTESIAN_POINT('Origin',(36.65,34.5,-20.)); +#1444=CARTESIAN_POINT('',(40.65,24.5511007311823,-34.3968539389312)); +#1445=CARTESIAN_POINT('Origin',(40.65,34.5,-20.)); +#1446=CARTESIAN_POINT('',(40.65,24.5511007311823,-34.3968539389312)); +#1447=CARTESIAN_POINT('Origin',(40.65,0.100000000000002,-17.5)); +#1448=CARTESIAN_POINT('',(36.65,-4.02620703476616,-14.6485979974995)); +#1449=CARTESIAN_POINT('',(40.65,-4.02620703476616,-14.6485979974995)); +#1450=CARTESIAN_POINT('Origin',(40.65,34.5,-20.)); +#1451=CARTESIAN_POINT('',(40.65,34.5,-13.)); +#1452=CARTESIAN_POINT('Origin',(40.65,34.5,-20.)); +#1453=CARTESIAN_POINT('',(36.65,34.5,-13.)); +#1454=CARTESIAN_POINT('',(40.65,34.5,-13.)); +#1455=CARTESIAN_POINT('Origin',(36.65,34.5,-20.)); +#1456=CARTESIAN_POINT('Origin',(40.65,34.5,-20.)); +#1457=CARTESIAN_POINT('',(-36.65,34.5,-13.)); +#1458=CARTESIAN_POINT('Origin',(-36.65,34.5,-20.)); +#1459=CARTESIAN_POINT('',(-40.65,34.5,-13.)); +#1460=CARTESIAN_POINT('',(40.65,34.5,-13.)); +#1461=CARTESIAN_POINT('Origin',(-40.65,34.5,-20.)); +#1462=CARTESIAN_POINT('Origin',(-36.65,-4.,0.)); +#1463=CARTESIAN_POINT('',(-36.55,-4.,0.)); +#1464=CARTESIAN_POINT('',(36.55,-4.,0.)); +#1465=CARTESIAN_POINT('Origin',(36.55,0.1,0.)); +#1466=CARTESIAN_POINT('',(36.65,0.1,0.)); +#1467=CARTESIAN_POINT('',(36.55,0.,0.)); +#1468=CARTESIAN_POINT('Origin',(-40.65,52.,0.)); +#1469=CARTESIAN_POINT('',(-40.65,0.0999999999999951,0.)); +#1470=CARTESIAN_POINT('Origin',(36.65,4.64630599083421E-32,0.)); +#1471=CARTESIAN_POINT('Origin',(-36.55,0.0999999999999979,0.)); +#1472=CARTESIAN_POINT('Origin',(36.55,0.1,0.)); +#1473=CARTESIAN_POINT('',(40.65,0.1,0.)); +#1474=CARTESIAN_POINT('Origin',(40.65,4.64630599083421E-32,0.)); +#1475=CARTESIAN_POINT('Origin',(-36.55,0.0999999999999979,0.)); +#1476=CARTESIAN_POINT('',(-36.55,0.,0.)); +#1477=CARTESIAN_POINT('',(-36.65,0.0999999999999978,0.)); +#1478=CARTESIAN_POINT('Origin',(-36.65,-4.64630599083421E-32,0.)); +#1479=CARTESIAN_POINT('Origin',(-36.65,52.,0.)); +#1480=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1484, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1481=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1484, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1482=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1480)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1484,#1486,#1487)) +REPRESENTATION_CONTEXT('','3D') +); +#1483=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1481)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1484,#1486,#1487)) +REPRESENTATION_CONTEXT('','3D') +); +#1484=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#1485=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT($,.METRE.) +); +#1486=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#1487=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#1488=SHAPE_DEFINITION_REPRESENTATION(#1489,#1490); +#1489=PRODUCT_DEFINITION_SHAPE('',$,#1492); +#1490=SHAPE_REPRESENTATION('',(#880),#1482); +#1491=PRODUCT_DEFINITION_CONTEXT('part definition',#1496,'design'); +#1492=PRODUCT_DEFINITION('link1-2','link1-2 v4',#1493,#1491); +#1493=PRODUCT_DEFINITION_FORMATION('',$,#1498); +#1494=PRODUCT_RELATED_PRODUCT_CATEGORY('link1-2 v4','link1-2 v4',(#1498)); +#1495=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#1496); +#1496=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#1497=PRODUCT_CONTEXT('part definition',#1496,'mechanical'); +#1498=PRODUCT('link1-2','link1-2 v4',$,(#1497)); +#1499=PRESENTATION_STYLE_ASSIGNMENT((#1501)); +#1500=PRESENTATION_STYLE_ASSIGNMENT((#1502)); +#1501=SURFACE_STYLE_USAGE(.BOTH.,#1503); +#1502=SURFACE_STYLE_USAGE(.BOTH.,#1504); +#1503=SURFACE_SIDE_STYLE('',(#1505)); +#1504=SURFACE_SIDE_STYLE('',(#1506)); +#1505=SURFACE_STYLE_FILL_AREA(#1507); +#1506=SURFACE_STYLE_FILL_AREA(#1508); +#1507=FILL_AREA_STYLE('Steel - Satin',(#1509)); +#1508=FILL_AREA_STYLE('Aluminum - Satin',(#1510)); +#1509=FILL_AREA_STYLE_COLOUR('Steel - Satin',#1511); +#1510=FILL_AREA_STYLE_COLOUR('Aluminum - Satin',#1512); +#1511=COLOUR_RGB('Steel - Satin',0.627450980392157,0.627450980392157,0.627450980392157); +#1512=COLOUR_RGB('Aluminum - Satin',0.96078431372549,0.96078431372549,0.964705882352941); +ENDSEC; +END-ISO-10303-21; diff --git a/hardware/follower_STEPs/link2-3_v0.2.0.step b/hardware/follower_STEPs/link2-3_v0.2.0.step new file mode 100644 index 0000000000000000000000000000000000000000..ade6f265852c59824dc0331998747d6a5d8d1df5 --- /dev/null +++ b/hardware/follower_STEPs/link2-3_v0.2.0.step @@ -0,0 +1,1923 @@ +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 */ 'link2-3_v0.2.0.step', +/* time_stamp */ '2025-10-08T20:56:10+02:00', +/* author */ (''), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v20.1', +/* originating_system */ 'Autodesk Translation Framework v14.17.0.0', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#1833); +#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#1840,#12); +#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#1832); +#13=STYLED_ITEM('',(#1850),#14); +#14=MANIFOLD_SOLID_BREP('Body1',#1057); +#15=FACE_BOUND('',#150,.T.); +#16=FACE_BOUND('',#151,.T.); +#17=FACE_BOUND('',#152,.T.); +#18=FACE_BOUND('',#153,.T.); +#19=FACE_BOUND('',#154,.T.); +#20=FACE_BOUND('',#155,.T.); +#21=FACE_BOUND('',#159,.T.); +#22=FACE_BOUND('',#160,.T.); +#23=FACE_BOUND('',#161,.T.); +#24=FACE_BOUND('',#162,.T.); +#25=FACE_BOUND('',#163,.T.); +#26=FACE_BOUND('',#165,.T.); +#27=FACE_BOUND('',#166,.T.); +#28=FACE_BOUND('',#167,.T.); +#29=FACE_BOUND('',#168,.T.); +#30=FACE_BOUND('',#169,.T.); +#31=FACE_BOUND('',#195,.T.); +#32=FACE_BOUND('',#196,.T.); +#33=FACE_BOUND('',#197,.T.); +#34=FACE_BOUND('',#198,.T.); +#35=FACE_BOUND('',#199,.T.); +#36=FACE_BOUND('',#205,.T.); +#37=FACE_BOUND('',#206,.T.); +#38=FACE_BOUND('',#207,.T.); +#39=FACE_BOUND('',#208,.T.); +#40=FACE_BOUND('',#209,.T.); +#41=FACE_BOUND('',#210,.T.); +#42=FACE_BOUND('',#215,.T.); +#43=FACE_BOUND('',#216,.T.); +#44=FACE_BOUND('',#217,.T.); +#45=FACE_BOUND('',#218,.T.); +#46=FACE_BOUND('',#219,.T.); +#47=ELLIPSE('',#1091,0.101189088558658,0.0999999999999995); +#48=ELLIPSE('',#1092,2.63091630252512,2.6); +#49=ELLIPSE('',#1093,0.101189088558658,0.1); +#50=ELLIPSE('',#1094,2.63091630252512,2.6); +#51=ELLIPSE('',#1099,0.101189088558658,0.0999999999999995); +#52=ELLIPSE('',#1100,2.63091630252512,2.6); +#53=ELLIPSE('',#1101,0.101189088558658,0.1); +#54=ELLIPSE('',#1102,2.63091630252512,2.6); +#55=ELLIPSE('',#1104,0.101189088558658,0.0999999999999995); +#56=ELLIPSE('',#1105,2.63091630252512,2.6); +#57=ELLIPSE('',#1106,0.101189088558658,0.1); +#58=ELLIPSE('',#1107,2.63091630252512,2.6); +#59=ELLIPSE('',#1110,0.101189088558658,0.0999999999999995); +#60=ELLIPSE('',#1111,2.63091630252512,2.6); +#61=ELLIPSE('',#1112,0.101189088558658,0.1); +#62=ELLIPSE('',#1113,2.63091630252512,2.6); +#63=PLANE('',#1089); +#64=PLANE('',#1090); +#65=PLANE('',#1098); +#66=PLANE('',#1103); +#67=PLANE('',#1108); +#68=PLANE('',#1109); +#69=PLANE('',#1114); +#70=PLANE('',#1116); +#71=PLANE('',#1119); +#72=PLANE('',#1130); +#73=PLANE('',#1144); +#74=PLANE('',#1189); +#75=PLANE('',#1190); +#76=PLANE('',#1191); +#77=PLANE('',#1194); +#78=PLANE('',#1195); +#79=PLANE('',#1198); +#80=FACE_OUTER_BOUND('',#134,.T.); +#81=FACE_OUTER_BOUND('',#135,.T.); +#82=FACE_OUTER_BOUND('',#136,.T.); +#83=FACE_OUTER_BOUND('',#137,.T.); +#84=FACE_OUTER_BOUND('',#138,.T.); +#85=FACE_OUTER_BOUND('',#139,.T.); +#86=FACE_OUTER_BOUND('',#140,.T.); +#87=FACE_OUTER_BOUND('',#141,.T.); +#88=FACE_OUTER_BOUND('',#142,.T.); +#89=FACE_OUTER_BOUND('',#143,.T.); +#90=FACE_OUTER_BOUND('',#144,.T.); +#91=FACE_OUTER_BOUND('',#145,.T.); +#92=FACE_OUTER_BOUND('',#146,.T.); +#93=FACE_OUTER_BOUND('',#147,.T.); +#94=FACE_OUTER_BOUND('',#148,.T.); +#95=FACE_OUTER_BOUND('',#149,.T.); +#96=FACE_OUTER_BOUND('',#156,.T.); +#97=FACE_OUTER_BOUND('',#157,.T.); +#98=FACE_OUTER_BOUND('',#158,.T.); +#99=FACE_OUTER_BOUND('',#164,.T.); +#100=FACE_OUTER_BOUND('',#170,.T.); +#101=FACE_OUTER_BOUND('',#171,.T.); +#102=FACE_OUTER_BOUND('',#172,.T.); +#103=FACE_OUTER_BOUND('',#173,.T.); +#104=FACE_OUTER_BOUND('',#174,.T.); +#105=FACE_OUTER_BOUND('',#175,.T.); +#106=FACE_OUTER_BOUND('',#176,.T.); +#107=FACE_OUTER_BOUND('',#177,.T.); +#108=FACE_OUTER_BOUND('',#178,.T.); +#109=FACE_OUTER_BOUND('',#179,.T.); +#110=FACE_OUTER_BOUND('',#180,.T.); +#111=FACE_OUTER_BOUND('',#181,.T.); +#112=FACE_OUTER_BOUND('',#182,.T.); +#113=FACE_OUTER_BOUND('',#183,.T.); +#114=FACE_OUTER_BOUND('',#184,.T.); +#115=FACE_OUTER_BOUND('',#185,.T.); +#116=FACE_OUTER_BOUND('',#186,.T.); +#117=FACE_OUTER_BOUND('',#187,.T.); +#118=FACE_OUTER_BOUND('',#188,.T.); +#119=FACE_OUTER_BOUND('',#189,.T.); +#120=FACE_OUTER_BOUND('',#190,.T.); +#121=FACE_OUTER_BOUND('',#191,.T.); +#122=FACE_OUTER_BOUND('',#192,.T.); +#123=FACE_OUTER_BOUND('',#193,.T.); +#124=FACE_OUTER_BOUND('',#194,.T.); +#125=FACE_OUTER_BOUND('',#200,.T.); +#126=FACE_OUTER_BOUND('',#201,.T.); +#127=FACE_OUTER_BOUND('',#202,.T.); +#128=FACE_OUTER_BOUND('',#203,.T.); +#129=FACE_OUTER_BOUND('',#204,.T.); +#130=FACE_OUTER_BOUND('',#211,.T.); +#131=FACE_OUTER_BOUND('',#212,.T.); +#132=FACE_OUTER_BOUND('',#213,.T.); +#133=FACE_OUTER_BOUND('',#214,.T.); +#134=EDGE_LOOP('',(#670,#671,#672,#673)); +#135=EDGE_LOOP('',(#674,#675,#676,#677)); +#136=EDGE_LOOP('',(#678,#679,#680,#681)); +#137=EDGE_LOOP('',(#682,#683,#684,#685)); +#138=EDGE_LOOP('',(#686,#687,#688,#689)); +#139=EDGE_LOOP('',(#690,#691,#692,#693)); +#140=EDGE_LOOP('',(#694,#695,#696,#697)); +#141=EDGE_LOOP('',(#698,#699,#700,#701,#702,#703,#704,#705,#706,#707)); +#142=EDGE_LOOP('',(#708,#709,#710,#711)); +#143=EDGE_LOOP('',(#712,#713,#714,#715,#716,#717,#718,#719,#720,#721)); +#144=EDGE_LOOP('',(#722,#723,#724,#725,#726,#727,#728,#729,#730,#731)); +#145=EDGE_LOOP('',(#732,#733,#734,#735)); +#146=EDGE_LOOP('',(#736,#737,#738,#739,#740,#741,#742,#743,#744,#745)); +#147=EDGE_LOOP('',(#746,#747,#748,#749)); +#148=EDGE_LOOP('',(#750,#751,#752,#753)); +#149=EDGE_LOOP('',(#754,#755,#756,#757)); +#150=EDGE_LOOP('',(#758)); +#151=EDGE_LOOP('',(#759)); +#152=EDGE_LOOP('',(#760)); +#153=EDGE_LOOP('',(#761)); +#154=EDGE_LOOP('',(#762)); +#155=EDGE_LOOP('',(#763)); +#156=EDGE_LOOP('',(#764,#765,#766,#767)); +#157=EDGE_LOOP('',(#768,#769,#770,#771)); +#158=EDGE_LOOP('',(#772,#773,#774,#775,#776,#777,#778,#779)); +#159=EDGE_LOOP('',(#780)); +#160=EDGE_LOOP('',(#781)); +#161=EDGE_LOOP('',(#782)); +#162=EDGE_LOOP('',(#783)); +#163=EDGE_LOOP('',(#784)); +#164=EDGE_LOOP('',(#785,#786,#787,#788,#789,#790,#791,#792,#793,#794,#795, +#796)); +#165=EDGE_LOOP('',(#797)); +#166=EDGE_LOOP('',(#798)); +#167=EDGE_LOOP('',(#799)); +#168=EDGE_LOOP('',(#800)); +#169=EDGE_LOOP('',(#801)); +#170=EDGE_LOOP('',(#802,#803,#804,#805)); +#171=EDGE_LOOP('',(#806,#807,#808,#809)); +#172=EDGE_LOOP('',(#810,#811,#812,#813)); +#173=EDGE_LOOP('',(#814,#815,#816,#817)); +#174=EDGE_LOOP('',(#818,#819,#820,#821)); +#175=EDGE_LOOP('',(#822,#823,#824,#825)); +#176=EDGE_LOOP('',(#826,#827,#828,#829)); +#177=EDGE_LOOP('',(#830,#831,#832,#833)); +#178=EDGE_LOOP('',(#834,#835,#836,#837)); +#179=EDGE_LOOP('',(#838,#839,#840,#841)); +#180=EDGE_LOOP('',(#842,#843,#844,#845)); +#181=EDGE_LOOP('',(#846,#847,#848,#849)); +#182=EDGE_LOOP('',(#850,#851,#852,#853)); +#183=EDGE_LOOP('',(#854,#855,#856,#857)); +#184=EDGE_LOOP('',(#858,#859,#860,#861)); +#185=EDGE_LOOP('',(#862,#863,#864,#865)); +#186=EDGE_LOOP('',(#866,#867,#868,#869)); +#187=EDGE_LOOP('',(#870,#871,#872,#873)); +#188=EDGE_LOOP('',(#874,#875,#876,#877)); +#189=EDGE_LOOP('',(#878,#879,#880,#881)); +#190=EDGE_LOOP('',(#882,#883,#884,#885)); +#191=EDGE_LOOP('',(#886,#887,#888,#889)); +#192=EDGE_LOOP('',(#890,#891,#892,#893)); +#193=EDGE_LOOP('',(#894,#895,#896,#897)); +#194=EDGE_LOOP('',(#898,#899,#900,#901,#902,#903,#904,#905,#906,#907,#908, +#909)); +#195=EDGE_LOOP('',(#910)); +#196=EDGE_LOOP('',(#911)); +#197=EDGE_LOOP('',(#912)); +#198=EDGE_LOOP('',(#913)); +#199=EDGE_LOOP('',(#914)); +#200=EDGE_LOOP('',(#915,#916,#917,#918)); +#201=EDGE_LOOP('',(#919,#920,#921,#922)); +#202=EDGE_LOOP('',(#923,#924,#925,#926)); +#203=EDGE_LOOP('',(#927,#928,#929,#930)); +#204=EDGE_LOOP('',(#931,#932,#933,#934)); +#205=EDGE_LOOP('',(#935)); +#206=EDGE_LOOP('',(#936)); +#207=EDGE_LOOP('',(#937)); +#208=EDGE_LOOP('',(#938)); +#209=EDGE_LOOP('',(#939)); +#210=EDGE_LOOP('',(#940)); +#211=EDGE_LOOP('',(#941,#942,#943,#944)); +#212=EDGE_LOOP('',(#945,#946,#947,#948)); +#213=EDGE_LOOP('',(#949,#950,#951,#952)); +#214=EDGE_LOOP('',(#953,#954,#955,#956,#957,#958,#959,#960)); +#215=EDGE_LOOP('',(#961)); +#216=EDGE_LOOP('',(#962)); +#217=EDGE_LOOP('',(#963)); +#218=EDGE_LOOP('',(#964)); +#219=EDGE_LOOP('',(#965)); +#220=LINE('',#1536,#294); +#221=LINE('',#1542,#295); +#222=LINE('',#1548,#296); +#223=LINE('',#1554,#297); +#224=LINE('',#1560,#298); +#225=LINE('',#1566,#299); +#226=LINE('',#1571,#300); +#227=LINE('',#1573,#301); +#228=LINE('',#1575,#302); +#229=LINE('',#1576,#303); +#230=LINE('',#1583,#304); +#231=LINE('',#1587,#305); +#232=LINE('',#1589,#306); +#233=LINE('',#1591,#307); +#234=LINE('',#1594,#308); +#235=LINE('',#1600,#309); +#236=LINE('',#1603,#310); +#237=LINE('',#1608,#311); +#238=LINE('',#1611,#312); +#239=LINE('',#1613,#313); +#240=LINE('',#1617,#314); +#241=LINE('',#1624,#315); +#242=LINE('',#1628,#316); +#243=LINE('',#1632,#317); +#244=LINE('',#1634,#318); +#245=LINE('',#1636,#319); +#246=LINE('',#1639,#320); +#247=LINE('',#1642,#321); +#248=LINE('',#1644,#322); +#249=LINE('',#1645,#323); +#250=LINE('',#1650,#324); +#251=LINE('',#1654,#325); +#252=LINE('',#1656,#326); +#253=LINE('',#1658,#327); +#254=LINE('',#1662,#328); +#255=LINE('',#1665,#329); +#256=LINE('',#1666,#330); +#257=LINE('',#1668,#331); +#258=LINE('',#1670,#332); +#259=LINE('',#1672,#333); +#260=LINE('',#1674,#334); +#261=LINE('',#1697,#335); +#262=LINE('',#1711,#336); +#263=LINE('',#1723,#337); +#264=LINE('',#1725,#338); +#265=LINE('',#1728,#339); +#266=LINE('',#1732,#340); +#267=LINE('',#1737,#341); +#268=LINE('',#1741,#342); +#269=LINE('',#1745,#343); +#270=LINE('',#1749,#344); +#271=LINE('',#1753,#345); +#272=LINE('',#1756,#346); +#273=LINE('',#1760,#347); +#274=LINE('',#1764,#348); +#275=LINE('',#1768,#349); +#276=LINE('',#1771,#350); +#277=LINE('',#1775,#351); +#278=LINE('',#1779,#352); +#279=LINE('',#1784,#353); +#280=LINE('',#1787,#354); +#281=LINE('',#1791,#355); +#282=LINE('',#1797,#356); +#283=LINE('',#1801,#357); +#284=LINE('',#1805,#358); +#285=LINE('',#1809,#359); +#286=LINE('',#1813,#360); +#287=LINE('',#1814,#361); +#288=LINE('',#1817,#362); +#289=LINE('',#1820,#363); +#290=LINE('',#1821,#364); +#291=LINE('',#1823,#365); +#292=LINE('',#1825,#366); +#293=LINE('',#1828,#367); +#294=VECTOR('',#1205,1.6); +#295=VECTOR('',#1212,1.6); +#296=VECTOR('',#1219,1.6); +#297=VECTOR('',#1226,1.6); +#298=VECTOR('',#1233,1.6); +#299=VECTOR('',#1240,1.6); +#300=VECTOR('',#1245,10.); +#301=VECTOR('',#1246,10.); +#302=VECTOR('',#1247,10.); +#303=VECTOR('',#1248,10.); +#304=VECTOR('',#1255,10.); +#305=VECTOR('',#1258,10.); +#306=VECTOR('',#1259,10.); +#307=VECTOR('',#1260,10.); +#308=VECTOR('',#1263,10.); +#309=VECTOR('',#1268,10.); +#310=VECTOR('',#1271,10.); +#311=VECTOR('',#1276,10.); +#312=VECTOR('',#1279,10.); +#313=VECTOR('',#1280,10.); +#314=VECTOR('',#1283,10.); +#315=VECTOR('',#1290,10.); +#316=VECTOR('',#1293,10.); +#317=VECTOR('',#1296,10.); +#318=VECTOR('',#1297,10.); +#319=VECTOR('',#1298,10.); +#320=VECTOR('',#1301,10.); +#321=VECTOR('',#1304,10.); +#322=VECTOR('',#1305,10.); +#323=VECTOR('',#1306,10.); +#324=VECTOR('',#1311,10.); +#325=VECTOR('',#1314,10.); +#326=VECTOR('',#1315,10.); +#327=VECTOR('',#1316,10.); +#328=VECTOR('',#1319,10.); +#329=VECTOR('',#1324,10.); +#330=VECTOR('',#1325,10.); +#331=VECTOR('',#1328,10.); +#332=VECTOR('',#1331,10.); +#333=VECTOR('',#1334,10.); +#334=VECTOR('',#1337,10.); +#335=VECTOR('',#1362,10.); +#336=VECTOR('',#1377,10.); +#337=VECTOR('',#1390,10.); +#338=VECTOR('',#1393,10.); +#339=VECTOR('',#1396,1.6); +#340=VECTOR('',#1401,1.6); +#341=VECTOR('',#1408,1.6); +#342=VECTOR('',#1413,1.6); +#343=VECTOR('',#1418,1.6); +#344=VECTOR('',#1423,1.6); +#345=VECTOR('',#1428,1.6); +#346=VECTOR('',#1431,1.6); +#347=VECTOR('',#1436,1.6); +#348=VECTOR('',#1441,1.6); +#349=VECTOR('',#1446,10.); +#350=VECTOR('',#1449,10.); +#351=VECTOR('',#1454,10.); +#352=VECTOR('',#1459,10.); +#353=VECTOR('',#1466,10.); +#354=VECTOR('',#1469,10.); +#355=VECTOR('',#1474,10.); +#356=VECTOR('',#1483,10.); +#357=VECTOR('',#1488,10.); +#358=VECTOR('',#1493,10.); +#359=VECTOR('',#1498,10.); +#360=VECTOR('',#1505,10.); +#361=VECTOR('',#1506,10.); +#362=VECTOR('',#1511,10.); +#363=VECTOR('',#1516,10.); +#364=VECTOR('',#1517,10.); +#365=VECTOR('',#1520,10.); +#366=VECTOR('',#1523,10.); +#367=VECTOR('',#1528,10.); +#368=CIRCLE('',#1072,1.6); +#369=CIRCLE('',#1073,1.6); +#370=CIRCLE('',#1075,1.6); +#371=CIRCLE('',#1076,1.6); +#372=CIRCLE('',#1078,1.6); +#373=CIRCLE('',#1079,1.6); +#374=CIRCLE('',#1081,1.6); +#375=CIRCLE('',#1082,1.6); +#376=CIRCLE('',#1084,1.6); +#377=CIRCLE('',#1085,1.6); +#378=CIRCLE('',#1087,1.6); +#379=CIRCLE('',#1088,1.6); +#380=CIRCLE('',#1096,28.5); +#381=CIRCLE('',#1097,28.5); +#382=CIRCLE('',#1120,28.5); +#383=CIRCLE('',#1121,3.50000000000001); +#384=CIRCLE('',#1122,21.5); +#385=CIRCLE('',#1123,3.50000000000001); +#386=CIRCLE('',#1124,28.5); +#387=CIRCLE('',#1125,1.6); +#388=CIRCLE('',#1126,1.6); +#389=CIRCLE('',#1127,1.6); +#390=CIRCLE('',#1128,1.6); +#391=CIRCLE('',#1129,1.6); +#392=CIRCLE('',#1131,28.5); +#393=CIRCLE('',#1132,3.5); +#394=CIRCLE('',#1133,21.5); +#395=CIRCLE('',#1134,21.5); +#396=CIRCLE('',#1135,21.5); +#397=CIRCLE('',#1136,3.5); +#398=CIRCLE('',#1137,28.5); +#399=CIRCLE('',#1138,1.6); +#400=CIRCLE('',#1139,1.6); +#401=CIRCLE('',#1140,1.6); +#402=CIRCLE('',#1141,1.6); +#403=CIRCLE('',#1142,1.6); +#404=CIRCLE('',#1146,1.6); +#405=CIRCLE('',#1148,1.6); +#406=CIRCLE('',#1150,1.6); +#407=CIRCLE('',#1152,1.6); +#408=CIRCLE('',#1154,1.6); +#409=CIRCLE('',#1156,1.6); +#410=CIRCLE('',#1158,1.6); +#411=CIRCLE('',#1160,1.6); +#412=CIRCLE('',#1162,1.6); +#413=CIRCLE('',#1164,1.6); +#414=CIRCLE('',#1166,21.5); +#415=CIRCLE('',#1168,21.5); +#416=CIRCLE('',#1170,3.5); +#417=CIRCLE('',#1172,28.5); +#418=CIRCLE('',#1174,28.5); +#419=CIRCLE('',#1176,3.5); +#420=CIRCLE('',#1178,21.5); +#421=CIRCLE('',#1180,28.5); +#422=CIRCLE('',#1182,3.50000000000001); +#423=CIRCLE('',#1184,21.5); +#424=CIRCLE('',#1186,3.50000000000001); +#425=CIRCLE('',#1188,28.5); +#426=VERTEX_POINT('',#1533); +#427=VERTEX_POINT('',#1535); +#428=VERTEX_POINT('',#1539); +#429=VERTEX_POINT('',#1541); +#430=VERTEX_POINT('',#1545); +#431=VERTEX_POINT('',#1547); +#432=VERTEX_POINT('',#1551); +#433=VERTEX_POINT('',#1553); +#434=VERTEX_POINT('',#1557); +#435=VERTEX_POINT('',#1559); +#436=VERTEX_POINT('',#1563); +#437=VERTEX_POINT('',#1565); +#438=VERTEX_POINT('',#1569); +#439=VERTEX_POINT('',#1570); +#440=VERTEX_POINT('',#1572); +#441=VERTEX_POINT('',#1574); +#442=VERTEX_POINT('',#1578); +#443=VERTEX_POINT('',#1580); +#444=VERTEX_POINT('',#1582); +#445=VERTEX_POINT('',#1584); +#446=VERTEX_POINT('',#1586); +#447=VERTEX_POINT('',#1588); +#448=VERTEX_POINT('',#1590); +#449=VERTEX_POINT('',#1592); +#450=VERTEX_POINT('',#1596); +#451=VERTEX_POINT('',#1597); +#452=VERTEX_POINT('',#1599); +#453=VERTEX_POINT('',#1601); +#454=VERTEX_POINT('',#1605); +#455=VERTEX_POINT('',#1607); +#456=VERTEX_POINT('',#1609); +#457=VERTEX_POINT('',#1612); +#458=VERTEX_POINT('',#1614); +#459=VERTEX_POINT('',#1616); +#460=VERTEX_POINT('',#1620); +#461=VERTEX_POINT('',#1621); +#462=VERTEX_POINT('',#1623); +#463=VERTEX_POINT('',#1625); +#464=VERTEX_POINT('',#1627); +#465=VERTEX_POINT('',#1629); +#466=VERTEX_POINT('',#1631); +#467=VERTEX_POINT('',#1633); +#468=VERTEX_POINT('',#1635); +#469=VERTEX_POINT('',#1637); +#470=VERTEX_POINT('',#1641); +#471=VERTEX_POINT('',#1643); +#472=VERTEX_POINT('',#1647); +#473=VERTEX_POINT('',#1649); +#474=VERTEX_POINT('',#1651); +#475=VERTEX_POINT('',#1653); +#476=VERTEX_POINT('',#1655); +#477=VERTEX_POINT('',#1657); +#478=VERTEX_POINT('',#1659); +#479=VERTEX_POINT('',#1661); +#480=VERTEX_POINT('',#1676); +#481=VERTEX_POINT('',#1678); +#482=VERTEX_POINT('',#1680); +#483=VERTEX_POINT('',#1682); +#484=VERTEX_POINT('',#1685); +#485=VERTEX_POINT('',#1687); +#486=VERTEX_POINT('',#1689); +#487=VERTEX_POINT('',#1691); +#488=VERTEX_POINT('',#1693); +#489=VERTEX_POINT('',#1696); +#490=VERTEX_POINT('',#1698); +#491=VERTEX_POINT('',#1700); +#492=VERTEX_POINT('',#1702); +#493=VERTEX_POINT('',#1704); +#494=VERTEX_POINT('',#1706); +#495=VERTEX_POINT('',#1708); +#496=VERTEX_POINT('',#1712); +#497=VERTEX_POINT('',#1714); +#498=VERTEX_POINT('',#1716); +#499=VERTEX_POINT('',#1718); +#500=VERTEX_POINT('',#1720); +#501=VERTEX_POINT('',#1727); +#502=VERTEX_POINT('',#1731); +#503=VERTEX_POINT('',#1735); +#504=VERTEX_POINT('',#1739); +#505=VERTEX_POINT('',#1743); +#506=VERTEX_POINT('',#1747); +#507=VERTEX_POINT('',#1751); +#508=VERTEX_POINT('',#1755); +#509=VERTEX_POINT('',#1759); +#510=VERTEX_POINT('',#1763); +#511=VERTEX_POINT('',#1767); +#512=VERTEX_POINT('',#1769); +#513=VERTEX_POINT('',#1773); +#514=VERTEX_POINT('',#1777); +#515=VERTEX_POINT('',#1783); +#516=VERTEX_POINT('',#1785); +#517=VERTEX_POINT('',#1789); +#518=VERTEX_POINT('',#1795); +#519=VERTEX_POINT('',#1799); +#520=VERTEX_POINT('',#1803); +#521=VERTEX_POINT('',#1807); +#522=EDGE_CURVE('',#426,#426,#368,.T.); +#523=EDGE_CURVE('',#426,#427,#220,.T.); +#524=EDGE_CURVE('',#427,#427,#369,.T.); +#525=EDGE_CURVE('',#428,#428,#370,.T.); +#526=EDGE_CURVE('',#428,#429,#221,.T.); +#527=EDGE_CURVE('',#429,#429,#371,.T.); +#528=EDGE_CURVE('',#430,#430,#372,.T.); +#529=EDGE_CURVE('',#430,#431,#222,.T.); +#530=EDGE_CURVE('',#431,#431,#373,.T.); +#531=EDGE_CURVE('',#432,#432,#374,.T.); +#532=EDGE_CURVE('',#432,#433,#223,.T.); +#533=EDGE_CURVE('',#433,#433,#375,.T.); +#534=EDGE_CURVE('',#434,#434,#376,.T.); +#535=EDGE_CURVE('',#434,#435,#224,.T.); +#536=EDGE_CURVE('',#435,#435,#377,.T.); +#537=EDGE_CURVE('',#436,#436,#378,.T.); +#538=EDGE_CURVE('',#436,#437,#225,.T.); +#539=EDGE_CURVE('',#437,#437,#379,.T.); +#540=EDGE_CURVE('',#438,#439,#226,.T.); +#541=EDGE_CURVE('',#438,#440,#227,.T.); +#542=EDGE_CURVE('',#441,#440,#228,.T.); +#543=EDGE_CURVE('',#439,#441,#229,.T.); +#544=EDGE_CURVE('',#439,#442,#47,.T.); +#545=EDGE_CURVE('',#443,#441,#48,.T.); +#546=EDGE_CURVE('',#444,#443,#230,.T.); +#547=EDGE_CURVE('',#445,#444,#49,.T.); +#548=EDGE_CURVE('',#446,#445,#231,.T.); +#549=EDGE_CURVE('',#447,#446,#232,.T.); +#550=EDGE_CURVE('',#448,#447,#233,.T.); +#551=EDGE_CURVE('',#449,#448,#50,.T.); +#552=EDGE_CURVE('',#442,#449,#234,.T.); +#553=EDGE_CURVE('',#450,#451,#380,.T.); +#554=EDGE_CURVE('',#452,#450,#235,.T.); +#555=EDGE_CURVE('',#453,#452,#381,.T.); +#556=EDGE_CURVE('',#451,#453,#236,.T.); +#557=EDGE_CURVE('',#454,#438,#51,.T.); +#558=EDGE_CURVE('',#455,#454,#237,.T.); +#559=EDGE_CURVE('',#456,#455,#52,.T.); +#560=EDGE_CURVE('',#452,#456,#238,.T.); +#561=EDGE_CURVE('',#457,#450,#239,.T.); +#562=EDGE_CURVE('',#458,#457,#53,.T.); +#563=EDGE_CURVE('',#459,#458,#240,.T.); +#564=EDGE_CURVE('',#440,#459,#54,.T.); +#565=EDGE_CURVE('',#460,#461,#55,.T.); +#566=EDGE_CURVE('',#460,#462,#241,.T.); +#567=EDGE_CURVE('',#463,#462,#56,.T.); +#568=EDGE_CURVE('',#464,#463,#242,.T.); +#569=EDGE_CURVE('',#465,#464,#57,.T.); +#570=EDGE_CURVE('',#466,#465,#243,.T.); +#571=EDGE_CURVE('',#467,#466,#244,.T.); +#572=EDGE_CURVE('',#468,#467,#245,.T.); +#573=EDGE_CURVE('',#469,#468,#58,.T.); +#574=EDGE_CURVE('',#461,#469,#246,.T.); +#575=EDGE_CURVE('',#470,#460,#247,.T.); +#576=EDGE_CURVE('',#470,#471,#248,.T.); +#577=EDGE_CURVE('',#462,#471,#249,.T.); +#578=EDGE_CURVE('',#472,#470,#59,.T.); +#579=EDGE_CURVE('',#473,#472,#250,.T.); +#580=EDGE_CURVE('',#474,#473,#60,.T.); +#581=EDGE_CURVE('',#475,#474,#251,.T.); +#582=EDGE_CURVE('',#475,#476,#252,.T.); +#583=EDGE_CURVE('',#477,#476,#253,.T.); +#584=EDGE_CURVE('',#478,#477,#61,.T.); +#585=EDGE_CURVE('',#479,#478,#254,.T.); +#586=EDGE_CURVE('',#471,#479,#62,.T.); +#587=EDGE_CURVE('',#473,#449,#255,.T.); +#588=EDGE_CURVE('',#442,#472,#256,.T.); +#589=EDGE_CURVE('',#470,#439,#257,.T.); +#590=EDGE_CURVE('',#438,#460,#258,.T.); +#591=EDGE_CURVE('',#448,#474,#259,.T.); +#592=EDGE_CURVE('',#461,#454,#260,.T.); +#593=EDGE_CURVE('',#447,#480,#382,.T.); +#594=EDGE_CURVE('',#480,#481,#383,.T.); +#595=EDGE_CURVE('',#482,#481,#384,.T.); +#596=EDGE_CURVE('',#482,#483,#385,.T.); +#597=EDGE_CURVE('',#483,#475,#386,.T.); +#598=EDGE_CURVE('',#484,#484,#387,.T.); +#599=EDGE_CURVE('',#485,#485,#388,.T.); +#600=EDGE_CURVE('',#486,#486,#389,.T.); +#601=EDGE_CURVE('',#487,#487,#390,.T.); +#602=EDGE_CURVE('',#488,#488,#391,.T.); +#603=EDGE_CURVE('',#489,#451,#261,.T.); +#604=EDGE_CURVE('',#489,#490,#392,.T.); +#605=EDGE_CURVE('',#490,#491,#393,.T.); +#606=EDGE_CURVE('',#491,#492,#394,.T.); +#607=EDGE_CURVE('',#492,#493,#395,.T.); +#608=EDGE_CURVE('',#493,#494,#396,.T.); +#609=EDGE_CURVE('',#494,#495,#397,.T.); +#610=EDGE_CURVE('',#495,#466,#398,.T.); +#611=EDGE_CURVE('',#465,#457,#262,.T.); +#612=EDGE_CURVE('',#496,#496,#399,.T.); +#613=EDGE_CURVE('',#497,#497,#400,.T.); +#614=EDGE_CURVE('',#498,#498,#401,.T.); +#615=EDGE_CURVE('',#499,#499,#402,.T.); +#616=EDGE_CURVE('',#500,#500,#403,.T.); +#617=EDGE_CURVE('',#458,#464,#263,.T.); +#618=EDGE_CURVE('',#463,#459,#264,.T.); +#619=EDGE_CURVE('',#488,#501,#265,.T.); +#620=EDGE_CURVE('',#501,#501,#404,.T.); +#621=EDGE_CURVE('',#487,#502,#266,.T.); +#622=EDGE_CURVE('',#502,#502,#405,.T.); +#623=EDGE_CURVE('',#503,#503,#406,.T.); +#624=EDGE_CURVE('',#503,#500,#267,.T.); +#625=EDGE_CURVE('',#504,#504,#407,.T.); +#626=EDGE_CURVE('',#504,#499,#268,.T.); +#627=EDGE_CURVE('',#505,#505,#408,.T.); +#628=EDGE_CURVE('',#505,#498,#269,.T.); +#629=EDGE_CURVE('',#506,#506,#409,.T.); +#630=EDGE_CURVE('',#506,#497,#270,.T.); +#631=EDGE_CURVE('',#507,#507,#410,.T.); +#632=EDGE_CURVE('',#507,#496,#271,.T.); +#633=EDGE_CURVE('',#486,#508,#272,.T.); +#634=EDGE_CURVE('',#508,#508,#411,.T.); +#635=EDGE_CURVE('',#485,#509,#273,.T.); +#636=EDGE_CURVE('',#509,#509,#412,.T.); +#637=EDGE_CURVE('',#484,#510,#274,.T.); +#638=EDGE_CURVE('',#510,#510,#413,.T.); +#639=EDGE_CURVE('',#511,#492,#275,.T.); +#640=EDGE_CURVE('',#511,#512,#414,.T.); +#641=EDGE_CURVE('',#512,#493,#276,.T.); +#642=EDGE_CURVE('',#512,#513,#415,.T.); +#643=EDGE_CURVE('',#513,#494,#277,.T.); +#644=EDGE_CURVE('',#514,#513,#416,.T.); +#645=EDGE_CURVE('',#514,#495,#278,.T.); +#646=EDGE_CURVE('',#467,#514,#417,.T.); +#647=EDGE_CURVE('',#515,#489,#279,.T.); +#648=EDGE_CURVE('',#516,#515,#418,.T.); +#649=EDGE_CURVE('',#516,#490,#280,.T.); +#650=EDGE_CURVE('',#517,#516,#419,.T.); +#651=EDGE_CURVE('',#517,#491,#281,.T.); +#652=EDGE_CURVE('',#517,#511,#420,.T.); +#653=EDGE_CURVE('',#476,#518,#421,.T.); +#654=EDGE_CURVE('',#483,#518,#282,.T.); +#655=EDGE_CURVE('',#518,#519,#422,.T.); +#656=EDGE_CURVE('',#482,#519,#283,.T.); +#657=EDGE_CURVE('',#519,#520,#423,.T.); +#658=EDGE_CURVE('',#481,#520,#284,.T.); +#659=EDGE_CURVE('',#520,#521,#424,.T.); +#660=EDGE_CURVE('',#480,#521,#285,.T.); +#661=EDGE_CURVE('',#521,#446,#425,.T.); +#662=EDGE_CURVE('',#468,#456,#286,.T.); +#663=EDGE_CURVE('',#515,#453,#287,.T.); +#664=EDGE_CURVE('',#455,#469,#288,.T.); +#665=EDGE_CURVE('',#471,#441,#289,.T.); +#666=EDGE_CURVE('',#443,#479,#290,.T.); +#667=EDGE_CURVE('',#440,#462,#291,.T.); +#668=EDGE_CURVE('',#478,#444,#292,.T.); +#669=EDGE_CURVE('',#445,#477,#293,.T.); +#670=ORIENTED_EDGE('',*,*,#522,.F.); +#671=ORIENTED_EDGE('',*,*,#523,.T.); +#672=ORIENTED_EDGE('',*,*,#524,.F.); +#673=ORIENTED_EDGE('',*,*,#523,.F.); +#674=ORIENTED_EDGE('',*,*,#525,.F.); +#675=ORIENTED_EDGE('',*,*,#526,.T.); +#676=ORIENTED_EDGE('',*,*,#527,.F.); +#677=ORIENTED_EDGE('',*,*,#526,.F.); +#678=ORIENTED_EDGE('',*,*,#528,.F.); +#679=ORIENTED_EDGE('',*,*,#529,.T.); +#680=ORIENTED_EDGE('',*,*,#530,.F.); +#681=ORIENTED_EDGE('',*,*,#529,.F.); +#682=ORIENTED_EDGE('',*,*,#531,.F.); +#683=ORIENTED_EDGE('',*,*,#532,.T.); +#684=ORIENTED_EDGE('',*,*,#533,.F.); +#685=ORIENTED_EDGE('',*,*,#532,.F.); +#686=ORIENTED_EDGE('',*,*,#534,.F.); +#687=ORIENTED_EDGE('',*,*,#535,.T.); +#688=ORIENTED_EDGE('',*,*,#536,.F.); +#689=ORIENTED_EDGE('',*,*,#535,.F.); +#690=ORIENTED_EDGE('',*,*,#537,.F.); +#691=ORIENTED_EDGE('',*,*,#538,.T.); +#692=ORIENTED_EDGE('',*,*,#539,.F.); +#693=ORIENTED_EDGE('',*,*,#538,.F.); +#694=ORIENTED_EDGE('',*,*,#540,.F.); +#695=ORIENTED_EDGE('',*,*,#541,.T.); +#696=ORIENTED_EDGE('',*,*,#542,.F.); +#697=ORIENTED_EDGE('',*,*,#543,.F.); +#698=ORIENTED_EDGE('',*,*,#544,.F.); +#699=ORIENTED_EDGE('',*,*,#543,.T.); +#700=ORIENTED_EDGE('',*,*,#545,.F.); +#701=ORIENTED_EDGE('',*,*,#546,.F.); +#702=ORIENTED_EDGE('',*,*,#547,.F.); +#703=ORIENTED_EDGE('',*,*,#548,.F.); +#704=ORIENTED_EDGE('',*,*,#549,.F.); +#705=ORIENTED_EDGE('',*,*,#550,.F.); +#706=ORIENTED_EDGE('',*,*,#551,.F.); +#707=ORIENTED_EDGE('',*,*,#552,.F.); +#708=ORIENTED_EDGE('',*,*,#553,.F.); +#709=ORIENTED_EDGE('',*,*,#554,.F.); +#710=ORIENTED_EDGE('',*,*,#555,.F.); +#711=ORIENTED_EDGE('',*,*,#556,.F.); +#712=ORIENTED_EDGE('',*,*,#557,.F.); +#713=ORIENTED_EDGE('',*,*,#558,.F.); +#714=ORIENTED_EDGE('',*,*,#559,.F.); +#715=ORIENTED_EDGE('',*,*,#560,.F.); +#716=ORIENTED_EDGE('',*,*,#554,.T.); +#717=ORIENTED_EDGE('',*,*,#561,.F.); +#718=ORIENTED_EDGE('',*,*,#562,.F.); +#719=ORIENTED_EDGE('',*,*,#563,.F.); +#720=ORIENTED_EDGE('',*,*,#564,.F.); +#721=ORIENTED_EDGE('',*,*,#541,.F.); +#722=ORIENTED_EDGE('',*,*,#565,.F.); +#723=ORIENTED_EDGE('',*,*,#566,.T.); +#724=ORIENTED_EDGE('',*,*,#567,.F.); +#725=ORIENTED_EDGE('',*,*,#568,.F.); +#726=ORIENTED_EDGE('',*,*,#569,.F.); +#727=ORIENTED_EDGE('',*,*,#570,.F.); +#728=ORIENTED_EDGE('',*,*,#571,.F.); +#729=ORIENTED_EDGE('',*,*,#572,.F.); +#730=ORIENTED_EDGE('',*,*,#573,.F.); +#731=ORIENTED_EDGE('',*,*,#574,.F.); +#732=ORIENTED_EDGE('',*,*,#575,.F.); +#733=ORIENTED_EDGE('',*,*,#576,.T.); +#734=ORIENTED_EDGE('',*,*,#577,.F.); +#735=ORIENTED_EDGE('',*,*,#566,.F.); +#736=ORIENTED_EDGE('',*,*,#578,.F.); +#737=ORIENTED_EDGE('',*,*,#579,.F.); +#738=ORIENTED_EDGE('',*,*,#580,.F.); +#739=ORIENTED_EDGE('',*,*,#581,.F.); +#740=ORIENTED_EDGE('',*,*,#582,.T.); +#741=ORIENTED_EDGE('',*,*,#583,.F.); +#742=ORIENTED_EDGE('',*,*,#584,.F.); +#743=ORIENTED_EDGE('',*,*,#585,.F.); +#744=ORIENTED_EDGE('',*,*,#586,.F.); +#745=ORIENTED_EDGE('',*,*,#576,.F.); +#746=ORIENTED_EDGE('',*,*,#552,.T.); +#747=ORIENTED_EDGE('',*,*,#587,.F.); +#748=ORIENTED_EDGE('',*,*,#579,.T.); +#749=ORIENTED_EDGE('',*,*,#588,.F.); +#750=ORIENTED_EDGE('',*,*,#544,.T.); +#751=ORIENTED_EDGE('',*,*,#588,.T.); +#752=ORIENTED_EDGE('',*,*,#578,.T.); +#753=ORIENTED_EDGE('',*,*,#589,.T.); +#754=ORIENTED_EDGE('',*,*,#540,.T.); +#755=ORIENTED_EDGE('',*,*,#589,.F.); +#756=ORIENTED_EDGE('',*,*,#575,.T.); +#757=ORIENTED_EDGE('',*,*,#590,.F.); +#758=ORIENTED_EDGE('',*,*,#522,.T.); +#759=ORIENTED_EDGE('',*,*,#525,.T.); +#760=ORIENTED_EDGE('',*,*,#528,.T.); +#761=ORIENTED_EDGE('',*,*,#531,.T.); +#762=ORIENTED_EDGE('',*,*,#534,.T.); +#763=ORIENTED_EDGE('',*,*,#537,.T.); +#764=ORIENTED_EDGE('',*,*,#551,.T.); +#765=ORIENTED_EDGE('',*,*,#591,.T.); +#766=ORIENTED_EDGE('',*,*,#580,.T.); +#767=ORIENTED_EDGE('',*,*,#587,.T.); +#768=ORIENTED_EDGE('',*,*,#557,.T.); +#769=ORIENTED_EDGE('',*,*,#590,.T.); +#770=ORIENTED_EDGE('',*,*,#565,.T.); +#771=ORIENTED_EDGE('',*,*,#592,.T.); +#772=ORIENTED_EDGE('',*,*,#550,.T.); +#773=ORIENTED_EDGE('',*,*,#593,.T.); +#774=ORIENTED_EDGE('',*,*,#594,.T.); +#775=ORIENTED_EDGE('',*,*,#595,.F.); +#776=ORIENTED_EDGE('',*,*,#596,.T.); +#777=ORIENTED_EDGE('',*,*,#597,.T.); +#778=ORIENTED_EDGE('',*,*,#581,.T.); +#779=ORIENTED_EDGE('',*,*,#591,.F.); +#780=ORIENTED_EDGE('',*,*,#598,.T.); +#781=ORIENTED_EDGE('',*,*,#599,.T.); +#782=ORIENTED_EDGE('',*,*,#600,.T.); +#783=ORIENTED_EDGE('',*,*,#601,.T.); +#784=ORIENTED_EDGE('',*,*,#602,.T.); +#785=ORIENTED_EDGE('',*,*,#561,.T.); +#786=ORIENTED_EDGE('',*,*,#553,.T.); +#787=ORIENTED_EDGE('',*,*,#603,.F.); +#788=ORIENTED_EDGE('',*,*,#604,.T.); +#789=ORIENTED_EDGE('',*,*,#605,.T.); +#790=ORIENTED_EDGE('',*,*,#606,.T.); +#791=ORIENTED_EDGE('',*,*,#607,.T.); +#792=ORIENTED_EDGE('',*,*,#608,.T.); +#793=ORIENTED_EDGE('',*,*,#609,.T.); +#794=ORIENTED_EDGE('',*,*,#610,.T.); +#795=ORIENTED_EDGE('',*,*,#570,.T.); +#796=ORIENTED_EDGE('',*,*,#611,.T.); +#797=ORIENTED_EDGE('',*,*,#612,.T.); +#798=ORIENTED_EDGE('',*,*,#613,.T.); +#799=ORIENTED_EDGE('',*,*,#614,.T.); +#800=ORIENTED_EDGE('',*,*,#615,.T.); +#801=ORIENTED_EDGE('',*,*,#616,.T.); +#802=ORIENTED_EDGE('',*,*,#562,.T.); +#803=ORIENTED_EDGE('',*,*,#611,.F.); +#804=ORIENTED_EDGE('',*,*,#569,.T.); +#805=ORIENTED_EDGE('',*,*,#617,.F.); +#806=ORIENTED_EDGE('',*,*,#563,.T.); +#807=ORIENTED_EDGE('',*,*,#617,.T.); +#808=ORIENTED_EDGE('',*,*,#568,.T.); +#809=ORIENTED_EDGE('',*,*,#618,.T.); +#810=ORIENTED_EDGE('',*,*,#602,.F.); +#811=ORIENTED_EDGE('',*,*,#619,.T.); +#812=ORIENTED_EDGE('',*,*,#620,.F.); +#813=ORIENTED_EDGE('',*,*,#619,.F.); +#814=ORIENTED_EDGE('',*,*,#601,.F.); +#815=ORIENTED_EDGE('',*,*,#621,.T.); +#816=ORIENTED_EDGE('',*,*,#622,.F.); +#817=ORIENTED_EDGE('',*,*,#621,.F.); +#818=ORIENTED_EDGE('',*,*,#623,.F.); +#819=ORIENTED_EDGE('',*,*,#624,.T.); +#820=ORIENTED_EDGE('',*,*,#616,.F.); +#821=ORIENTED_EDGE('',*,*,#624,.F.); +#822=ORIENTED_EDGE('',*,*,#625,.F.); +#823=ORIENTED_EDGE('',*,*,#626,.T.); +#824=ORIENTED_EDGE('',*,*,#615,.F.); +#825=ORIENTED_EDGE('',*,*,#626,.F.); +#826=ORIENTED_EDGE('',*,*,#627,.F.); +#827=ORIENTED_EDGE('',*,*,#628,.T.); +#828=ORIENTED_EDGE('',*,*,#614,.F.); +#829=ORIENTED_EDGE('',*,*,#628,.F.); +#830=ORIENTED_EDGE('',*,*,#629,.F.); +#831=ORIENTED_EDGE('',*,*,#630,.T.); +#832=ORIENTED_EDGE('',*,*,#613,.F.); +#833=ORIENTED_EDGE('',*,*,#630,.F.); +#834=ORIENTED_EDGE('',*,*,#631,.F.); +#835=ORIENTED_EDGE('',*,*,#632,.T.); +#836=ORIENTED_EDGE('',*,*,#612,.F.); +#837=ORIENTED_EDGE('',*,*,#632,.F.); +#838=ORIENTED_EDGE('',*,*,#600,.F.); +#839=ORIENTED_EDGE('',*,*,#633,.T.); +#840=ORIENTED_EDGE('',*,*,#634,.F.); +#841=ORIENTED_EDGE('',*,*,#633,.F.); +#842=ORIENTED_EDGE('',*,*,#599,.F.); +#843=ORIENTED_EDGE('',*,*,#635,.T.); +#844=ORIENTED_EDGE('',*,*,#636,.F.); +#845=ORIENTED_EDGE('',*,*,#635,.F.); +#846=ORIENTED_EDGE('',*,*,#598,.F.); +#847=ORIENTED_EDGE('',*,*,#637,.T.); +#848=ORIENTED_EDGE('',*,*,#638,.F.); +#849=ORIENTED_EDGE('',*,*,#637,.F.); +#850=ORIENTED_EDGE('',*,*,#607,.F.); +#851=ORIENTED_EDGE('',*,*,#639,.F.); +#852=ORIENTED_EDGE('',*,*,#640,.T.); +#853=ORIENTED_EDGE('',*,*,#641,.T.); +#854=ORIENTED_EDGE('',*,*,#608,.F.); +#855=ORIENTED_EDGE('',*,*,#641,.F.); +#856=ORIENTED_EDGE('',*,*,#642,.T.); +#857=ORIENTED_EDGE('',*,*,#643,.T.); +#858=ORIENTED_EDGE('',*,*,#609,.F.); +#859=ORIENTED_EDGE('',*,*,#643,.F.); +#860=ORIENTED_EDGE('',*,*,#644,.F.); +#861=ORIENTED_EDGE('',*,*,#645,.T.); +#862=ORIENTED_EDGE('',*,*,#610,.F.); +#863=ORIENTED_EDGE('',*,*,#645,.F.); +#864=ORIENTED_EDGE('',*,*,#646,.F.); +#865=ORIENTED_EDGE('',*,*,#571,.T.); +#866=ORIENTED_EDGE('',*,*,#604,.F.); +#867=ORIENTED_EDGE('',*,*,#647,.F.); +#868=ORIENTED_EDGE('',*,*,#648,.F.); +#869=ORIENTED_EDGE('',*,*,#649,.T.); +#870=ORIENTED_EDGE('',*,*,#605,.F.); +#871=ORIENTED_EDGE('',*,*,#649,.F.); +#872=ORIENTED_EDGE('',*,*,#650,.F.); +#873=ORIENTED_EDGE('',*,*,#651,.T.); +#874=ORIENTED_EDGE('',*,*,#606,.F.); +#875=ORIENTED_EDGE('',*,*,#651,.F.); +#876=ORIENTED_EDGE('',*,*,#652,.T.); +#877=ORIENTED_EDGE('',*,*,#639,.T.); +#878=ORIENTED_EDGE('',*,*,#653,.F.); +#879=ORIENTED_EDGE('',*,*,#582,.F.); +#880=ORIENTED_EDGE('',*,*,#597,.F.); +#881=ORIENTED_EDGE('',*,*,#654,.T.); +#882=ORIENTED_EDGE('',*,*,#655,.F.); +#883=ORIENTED_EDGE('',*,*,#654,.F.); +#884=ORIENTED_EDGE('',*,*,#596,.F.); +#885=ORIENTED_EDGE('',*,*,#656,.T.); +#886=ORIENTED_EDGE('',*,*,#657,.F.); +#887=ORIENTED_EDGE('',*,*,#656,.F.); +#888=ORIENTED_EDGE('',*,*,#595,.T.); +#889=ORIENTED_EDGE('',*,*,#658,.T.); +#890=ORIENTED_EDGE('',*,*,#659,.F.); +#891=ORIENTED_EDGE('',*,*,#658,.F.); +#892=ORIENTED_EDGE('',*,*,#594,.F.); +#893=ORIENTED_EDGE('',*,*,#660,.T.); +#894=ORIENTED_EDGE('',*,*,#661,.F.); +#895=ORIENTED_EDGE('',*,*,#660,.F.); +#896=ORIENTED_EDGE('',*,*,#593,.F.); +#897=ORIENTED_EDGE('',*,*,#549,.T.); +#898=ORIENTED_EDGE('',*,*,#560,.T.); +#899=ORIENTED_EDGE('',*,*,#662,.F.); +#900=ORIENTED_EDGE('',*,*,#572,.T.); +#901=ORIENTED_EDGE('',*,*,#646,.T.); +#902=ORIENTED_EDGE('',*,*,#644,.T.); +#903=ORIENTED_EDGE('',*,*,#642,.F.); +#904=ORIENTED_EDGE('',*,*,#640,.F.); +#905=ORIENTED_EDGE('',*,*,#652,.F.); +#906=ORIENTED_EDGE('',*,*,#650,.T.); +#907=ORIENTED_EDGE('',*,*,#648,.T.); +#908=ORIENTED_EDGE('',*,*,#663,.T.); +#909=ORIENTED_EDGE('',*,*,#555,.T.); +#910=ORIENTED_EDGE('',*,*,#623,.T.); +#911=ORIENTED_EDGE('',*,*,#625,.T.); +#912=ORIENTED_EDGE('',*,*,#627,.T.); +#913=ORIENTED_EDGE('',*,*,#629,.T.); +#914=ORIENTED_EDGE('',*,*,#631,.T.); +#915=ORIENTED_EDGE('',*,*,#556,.T.); +#916=ORIENTED_EDGE('',*,*,#663,.F.); +#917=ORIENTED_EDGE('',*,*,#647,.T.); +#918=ORIENTED_EDGE('',*,*,#603,.T.); +#919=ORIENTED_EDGE('',*,*,#558,.T.); +#920=ORIENTED_EDGE('',*,*,#592,.F.); +#921=ORIENTED_EDGE('',*,*,#574,.T.); +#922=ORIENTED_EDGE('',*,*,#664,.F.); +#923=ORIENTED_EDGE('',*,*,#559,.T.); +#924=ORIENTED_EDGE('',*,*,#664,.T.); +#925=ORIENTED_EDGE('',*,*,#573,.T.); +#926=ORIENTED_EDGE('',*,*,#662,.T.); +#927=ORIENTED_EDGE('',*,*,#545,.T.); +#928=ORIENTED_EDGE('',*,*,#665,.F.); +#929=ORIENTED_EDGE('',*,*,#586,.T.); +#930=ORIENTED_EDGE('',*,*,#666,.F.); +#931=ORIENTED_EDGE('',*,*,#542,.T.); +#932=ORIENTED_EDGE('',*,*,#667,.T.); +#933=ORIENTED_EDGE('',*,*,#577,.T.); +#934=ORIENTED_EDGE('',*,*,#665,.T.); +#935=ORIENTED_EDGE('',*,*,#524,.T.); +#936=ORIENTED_EDGE('',*,*,#527,.T.); +#937=ORIENTED_EDGE('',*,*,#530,.T.); +#938=ORIENTED_EDGE('',*,*,#533,.T.); +#939=ORIENTED_EDGE('',*,*,#536,.T.); +#940=ORIENTED_EDGE('',*,*,#539,.T.); +#941=ORIENTED_EDGE('',*,*,#546,.T.); +#942=ORIENTED_EDGE('',*,*,#666,.T.); +#943=ORIENTED_EDGE('',*,*,#585,.T.); +#944=ORIENTED_EDGE('',*,*,#668,.T.); +#945=ORIENTED_EDGE('',*,*,#564,.T.); +#946=ORIENTED_EDGE('',*,*,#618,.F.); +#947=ORIENTED_EDGE('',*,*,#567,.T.); +#948=ORIENTED_EDGE('',*,*,#667,.F.); +#949=ORIENTED_EDGE('',*,*,#547,.T.); +#950=ORIENTED_EDGE('',*,*,#668,.F.); +#951=ORIENTED_EDGE('',*,*,#584,.T.); +#952=ORIENTED_EDGE('',*,*,#669,.F.); +#953=ORIENTED_EDGE('',*,*,#548,.T.); +#954=ORIENTED_EDGE('',*,*,#669,.T.); +#955=ORIENTED_EDGE('',*,*,#583,.T.); +#956=ORIENTED_EDGE('',*,*,#653,.T.); +#957=ORIENTED_EDGE('',*,*,#655,.T.); +#958=ORIENTED_EDGE('',*,*,#657,.T.); +#959=ORIENTED_EDGE('',*,*,#659,.T.); +#960=ORIENTED_EDGE('',*,*,#661,.T.); +#961=ORIENTED_EDGE('',*,*,#620,.T.); +#962=ORIENTED_EDGE('',*,*,#622,.T.); +#963=ORIENTED_EDGE('',*,*,#634,.T.); +#964=ORIENTED_EDGE('',*,*,#636,.T.); +#965=ORIENTED_EDGE('',*,*,#638,.T.); +#966=CYLINDRICAL_SURFACE('',#1071,1.6); +#967=CYLINDRICAL_SURFACE('',#1074,1.6); +#968=CYLINDRICAL_SURFACE('',#1077,1.6); +#969=CYLINDRICAL_SURFACE('',#1080,1.6); +#970=CYLINDRICAL_SURFACE('',#1083,1.6); +#971=CYLINDRICAL_SURFACE('',#1086,1.6); +#972=CYLINDRICAL_SURFACE('',#1095,28.5); +#973=CYLINDRICAL_SURFACE('',#1115,0.0999999999999995); +#974=CYLINDRICAL_SURFACE('',#1117,2.6); +#975=CYLINDRICAL_SURFACE('',#1118,0.0999999999999995); +#976=CYLINDRICAL_SURFACE('',#1143,0.1); +#977=CYLINDRICAL_SURFACE('',#1145,1.6); +#978=CYLINDRICAL_SURFACE('',#1147,1.6); +#979=CYLINDRICAL_SURFACE('',#1149,1.6); +#980=CYLINDRICAL_SURFACE('',#1151,1.6); +#981=CYLINDRICAL_SURFACE('',#1153,1.6); +#982=CYLINDRICAL_SURFACE('',#1155,1.6); +#983=CYLINDRICAL_SURFACE('',#1157,1.6); +#984=CYLINDRICAL_SURFACE('',#1159,1.6); +#985=CYLINDRICAL_SURFACE('',#1161,1.6); +#986=CYLINDRICAL_SURFACE('',#1163,1.6); +#987=CYLINDRICAL_SURFACE('',#1165,21.5); +#988=CYLINDRICAL_SURFACE('',#1167,21.5); +#989=CYLINDRICAL_SURFACE('',#1169,3.5); +#990=CYLINDRICAL_SURFACE('',#1171,28.5); +#991=CYLINDRICAL_SURFACE('',#1173,28.5); +#992=CYLINDRICAL_SURFACE('',#1175,3.5); +#993=CYLINDRICAL_SURFACE('',#1177,21.5); +#994=CYLINDRICAL_SURFACE('',#1179,28.5); +#995=CYLINDRICAL_SURFACE('',#1181,3.50000000000001); +#996=CYLINDRICAL_SURFACE('',#1183,21.5); +#997=CYLINDRICAL_SURFACE('',#1185,3.50000000000001); +#998=CYLINDRICAL_SURFACE('',#1187,28.5); +#999=CYLINDRICAL_SURFACE('',#1192,2.6); +#1000=CYLINDRICAL_SURFACE('',#1193,2.6); +#1001=CYLINDRICAL_SURFACE('',#1196,2.6); +#1002=CYLINDRICAL_SURFACE('',#1197,0.1); +#1003=ADVANCED_FACE('',(#80),#966,.F.); +#1004=ADVANCED_FACE('',(#81),#967,.F.); +#1005=ADVANCED_FACE('',(#82),#968,.F.); +#1006=ADVANCED_FACE('',(#83),#969,.F.); +#1007=ADVANCED_FACE('',(#84),#970,.F.); +#1008=ADVANCED_FACE('',(#85),#971,.F.); +#1009=ADVANCED_FACE('',(#86),#63,.F.); +#1010=ADVANCED_FACE('',(#87),#64,.F.); +#1011=ADVANCED_FACE('',(#88),#972,.T.); +#1012=ADVANCED_FACE('',(#89),#65,.F.); +#1013=ADVANCED_FACE('',(#90),#66,.F.); +#1014=ADVANCED_FACE('',(#91),#67,.F.); +#1015=ADVANCED_FACE('',(#92),#68,.F.); +#1016=ADVANCED_FACE('',(#93),#69,.F.); +#1017=ADVANCED_FACE('',(#94),#973,.F.); +#1018=ADVANCED_FACE('',(#95,#15,#16,#17,#18,#19,#20),#70,.F.); +#1019=ADVANCED_FACE('',(#96),#974,.T.); +#1020=ADVANCED_FACE('',(#97),#975,.F.); +#1021=ADVANCED_FACE('',(#98,#21,#22,#23,#24,#25),#71,.F.); +#1022=ADVANCED_FACE('',(#99,#26,#27,#28,#29,#30),#72,.T.); +#1023=ADVANCED_FACE('',(#100),#976,.F.); +#1024=ADVANCED_FACE('',(#101),#73,.T.); +#1025=ADVANCED_FACE('',(#102),#977,.F.); +#1026=ADVANCED_FACE('',(#103),#978,.F.); +#1027=ADVANCED_FACE('',(#104),#979,.F.); +#1028=ADVANCED_FACE('',(#105),#980,.F.); +#1029=ADVANCED_FACE('',(#106),#981,.F.); +#1030=ADVANCED_FACE('',(#107),#982,.F.); +#1031=ADVANCED_FACE('',(#108),#983,.F.); +#1032=ADVANCED_FACE('',(#109),#984,.F.); +#1033=ADVANCED_FACE('',(#110),#985,.F.); +#1034=ADVANCED_FACE('',(#111),#986,.F.); +#1035=ADVANCED_FACE('',(#112),#987,.F.); +#1036=ADVANCED_FACE('',(#113),#988,.F.); +#1037=ADVANCED_FACE('',(#114),#989,.T.); +#1038=ADVANCED_FACE('',(#115),#990,.T.); +#1039=ADVANCED_FACE('',(#116),#991,.T.); +#1040=ADVANCED_FACE('',(#117),#992,.T.); +#1041=ADVANCED_FACE('',(#118),#993,.F.); +#1042=ADVANCED_FACE('',(#119),#994,.T.); +#1043=ADVANCED_FACE('',(#120),#995,.T.); +#1044=ADVANCED_FACE('',(#121),#996,.F.); +#1045=ADVANCED_FACE('',(#122),#997,.T.); +#1046=ADVANCED_FACE('',(#123),#998,.T.); +#1047=ADVANCED_FACE('',(#124,#31,#32,#33,#34,#35),#74,.F.); +#1048=ADVANCED_FACE('',(#125),#75,.F.); +#1049=ADVANCED_FACE('',(#126),#76,.F.); +#1050=ADVANCED_FACE('',(#127),#999,.T.); +#1051=ADVANCED_FACE('',(#128),#1000,.T.); +#1052=ADVANCED_FACE('',(#129,#36,#37,#38,#39,#40,#41),#77,.T.); +#1053=ADVANCED_FACE('',(#130),#78,.T.); +#1054=ADVANCED_FACE('',(#131),#1001,.T.); +#1055=ADVANCED_FACE('',(#132),#1002,.F.); +#1056=ADVANCED_FACE('',(#133,#42,#43,#44,#45,#46),#79,.T.); +#1057=CLOSED_SHELL('',(#1003,#1004,#1005,#1006,#1007,#1008,#1009,#1010, +#1011,#1012,#1013,#1014,#1015,#1016,#1017,#1018,#1019,#1020,#1021,#1022, +#1023,#1024,#1025,#1026,#1027,#1028,#1029,#1030,#1031,#1032,#1033,#1034, +#1035,#1036,#1037,#1038,#1039,#1040,#1041,#1042,#1043,#1044,#1045,#1046, +#1047,#1048,#1049,#1050,#1051,#1052,#1053,#1054,#1055,#1056)); +#1058=DERIVED_UNIT_ELEMENT(#1060,1.); +#1059=DERIVED_UNIT_ELEMENT(#1835,-3.); +#1060=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT(.KILO.,.GRAM.) +); +#1061=DERIVED_UNIT((#1058,#1059)); +#1062=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(7850.),#1061); +#1063=PROPERTY_DEFINITION_REPRESENTATION(#1068,#1065); +#1064=PROPERTY_DEFINITION_REPRESENTATION(#1069,#1066); +#1065=REPRESENTATION('material name',(#1067),#1832); +#1066=REPRESENTATION('density',(#1062),#1832); +#1067=DESCRIPTIVE_REPRESENTATION_ITEM('Steel','Steel'); +#1068=PROPERTY_DEFINITION('material property','material name',#1842); +#1069=PROPERTY_DEFINITION('material property','density of part',#1842); +#1070=AXIS2_PLACEMENT_3D('',#1531,#1199,#1200); +#1071=AXIS2_PLACEMENT_3D('',#1532,#1201,#1202); +#1072=AXIS2_PLACEMENT_3D('',#1534,#1203,#1204); +#1073=AXIS2_PLACEMENT_3D('',#1537,#1206,#1207); +#1074=AXIS2_PLACEMENT_3D('',#1538,#1208,#1209); +#1075=AXIS2_PLACEMENT_3D('',#1540,#1210,#1211); +#1076=AXIS2_PLACEMENT_3D('',#1543,#1213,#1214); +#1077=AXIS2_PLACEMENT_3D('',#1544,#1215,#1216); +#1078=AXIS2_PLACEMENT_3D('',#1546,#1217,#1218); +#1079=AXIS2_PLACEMENT_3D('',#1549,#1220,#1221); +#1080=AXIS2_PLACEMENT_3D('',#1550,#1222,#1223); +#1081=AXIS2_PLACEMENT_3D('',#1552,#1224,#1225); +#1082=AXIS2_PLACEMENT_3D('',#1555,#1227,#1228); +#1083=AXIS2_PLACEMENT_3D('',#1556,#1229,#1230); +#1084=AXIS2_PLACEMENT_3D('',#1558,#1231,#1232); +#1085=AXIS2_PLACEMENT_3D('',#1561,#1234,#1235); +#1086=AXIS2_PLACEMENT_3D('',#1562,#1236,#1237); +#1087=AXIS2_PLACEMENT_3D('',#1564,#1238,#1239); +#1088=AXIS2_PLACEMENT_3D('',#1567,#1241,#1242); +#1089=AXIS2_PLACEMENT_3D('',#1568,#1243,#1244); +#1090=AXIS2_PLACEMENT_3D('',#1577,#1249,#1250); +#1091=AXIS2_PLACEMENT_3D('',#1579,#1251,#1252); +#1092=AXIS2_PLACEMENT_3D('',#1581,#1253,#1254); +#1093=AXIS2_PLACEMENT_3D('',#1585,#1256,#1257); +#1094=AXIS2_PLACEMENT_3D('',#1593,#1261,#1262); +#1095=AXIS2_PLACEMENT_3D('',#1595,#1264,#1265); +#1096=AXIS2_PLACEMENT_3D('',#1598,#1266,#1267); +#1097=AXIS2_PLACEMENT_3D('',#1602,#1269,#1270); +#1098=AXIS2_PLACEMENT_3D('',#1604,#1272,#1273); +#1099=AXIS2_PLACEMENT_3D('',#1606,#1274,#1275); +#1100=AXIS2_PLACEMENT_3D('',#1610,#1277,#1278); +#1101=AXIS2_PLACEMENT_3D('',#1615,#1281,#1282); +#1102=AXIS2_PLACEMENT_3D('',#1618,#1284,#1285); +#1103=AXIS2_PLACEMENT_3D('',#1619,#1286,#1287); +#1104=AXIS2_PLACEMENT_3D('',#1622,#1288,#1289); +#1105=AXIS2_PLACEMENT_3D('',#1626,#1291,#1292); +#1106=AXIS2_PLACEMENT_3D('',#1630,#1294,#1295); +#1107=AXIS2_PLACEMENT_3D('',#1638,#1299,#1300); +#1108=AXIS2_PLACEMENT_3D('',#1640,#1302,#1303); +#1109=AXIS2_PLACEMENT_3D('',#1646,#1307,#1308); +#1110=AXIS2_PLACEMENT_3D('',#1648,#1309,#1310); +#1111=AXIS2_PLACEMENT_3D('',#1652,#1312,#1313); +#1112=AXIS2_PLACEMENT_3D('',#1660,#1317,#1318); +#1113=AXIS2_PLACEMENT_3D('',#1663,#1320,#1321); +#1114=AXIS2_PLACEMENT_3D('',#1664,#1322,#1323); +#1115=AXIS2_PLACEMENT_3D('',#1667,#1326,#1327); +#1116=AXIS2_PLACEMENT_3D('',#1669,#1329,#1330); +#1117=AXIS2_PLACEMENT_3D('',#1671,#1332,#1333); +#1118=AXIS2_PLACEMENT_3D('',#1673,#1335,#1336); +#1119=AXIS2_PLACEMENT_3D('',#1675,#1338,#1339); +#1120=AXIS2_PLACEMENT_3D('',#1677,#1340,#1341); +#1121=AXIS2_PLACEMENT_3D('',#1679,#1342,#1343); +#1122=AXIS2_PLACEMENT_3D('',#1681,#1344,#1345); +#1123=AXIS2_PLACEMENT_3D('',#1683,#1346,#1347); +#1124=AXIS2_PLACEMENT_3D('',#1684,#1348,#1349); +#1125=AXIS2_PLACEMENT_3D('',#1686,#1350,#1351); +#1126=AXIS2_PLACEMENT_3D('',#1688,#1352,#1353); +#1127=AXIS2_PLACEMENT_3D('',#1690,#1354,#1355); +#1128=AXIS2_PLACEMENT_3D('',#1692,#1356,#1357); +#1129=AXIS2_PLACEMENT_3D('',#1694,#1358,#1359); +#1130=AXIS2_PLACEMENT_3D('',#1695,#1360,#1361); +#1131=AXIS2_PLACEMENT_3D('',#1699,#1363,#1364); +#1132=AXIS2_PLACEMENT_3D('',#1701,#1365,#1366); +#1133=AXIS2_PLACEMENT_3D('',#1703,#1367,#1368); +#1134=AXIS2_PLACEMENT_3D('',#1705,#1369,#1370); +#1135=AXIS2_PLACEMENT_3D('',#1707,#1371,#1372); +#1136=AXIS2_PLACEMENT_3D('',#1709,#1373,#1374); +#1137=AXIS2_PLACEMENT_3D('',#1710,#1375,#1376); +#1138=AXIS2_PLACEMENT_3D('',#1713,#1378,#1379); +#1139=AXIS2_PLACEMENT_3D('',#1715,#1380,#1381); +#1140=AXIS2_PLACEMENT_3D('',#1717,#1382,#1383); +#1141=AXIS2_PLACEMENT_3D('',#1719,#1384,#1385); +#1142=AXIS2_PLACEMENT_3D('',#1721,#1386,#1387); +#1143=AXIS2_PLACEMENT_3D('',#1722,#1388,#1389); +#1144=AXIS2_PLACEMENT_3D('',#1724,#1391,#1392); +#1145=AXIS2_PLACEMENT_3D('',#1726,#1394,#1395); +#1146=AXIS2_PLACEMENT_3D('',#1729,#1397,#1398); +#1147=AXIS2_PLACEMENT_3D('',#1730,#1399,#1400); +#1148=AXIS2_PLACEMENT_3D('',#1733,#1402,#1403); +#1149=AXIS2_PLACEMENT_3D('',#1734,#1404,#1405); +#1150=AXIS2_PLACEMENT_3D('',#1736,#1406,#1407); +#1151=AXIS2_PLACEMENT_3D('',#1738,#1409,#1410); +#1152=AXIS2_PLACEMENT_3D('',#1740,#1411,#1412); +#1153=AXIS2_PLACEMENT_3D('',#1742,#1414,#1415); +#1154=AXIS2_PLACEMENT_3D('',#1744,#1416,#1417); +#1155=AXIS2_PLACEMENT_3D('',#1746,#1419,#1420); +#1156=AXIS2_PLACEMENT_3D('',#1748,#1421,#1422); +#1157=AXIS2_PLACEMENT_3D('',#1750,#1424,#1425); +#1158=AXIS2_PLACEMENT_3D('',#1752,#1426,#1427); +#1159=AXIS2_PLACEMENT_3D('',#1754,#1429,#1430); +#1160=AXIS2_PLACEMENT_3D('',#1757,#1432,#1433); +#1161=AXIS2_PLACEMENT_3D('',#1758,#1434,#1435); +#1162=AXIS2_PLACEMENT_3D('',#1761,#1437,#1438); +#1163=AXIS2_PLACEMENT_3D('',#1762,#1439,#1440); +#1164=AXIS2_PLACEMENT_3D('',#1765,#1442,#1443); +#1165=AXIS2_PLACEMENT_3D('',#1766,#1444,#1445); +#1166=AXIS2_PLACEMENT_3D('',#1770,#1447,#1448); +#1167=AXIS2_PLACEMENT_3D('',#1772,#1450,#1451); +#1168=AXIS2_PLACEMENT_3D('',#1774,#1452,#1453); +#1169=AXIS2_PLACEMENT_3D('',#1776,#1455,#1456); +#1170=AXIS2_PLACEMENT_3D('',#1778,#1457,#1458); +#1171=AXIS2_PLACEMENT_3D('',#1780,#1460,#1461); +#1172=AXIS2_PLACEMENT_3D('',#1781,#1462,#1463); +#1173=AXIS2_PLACEMENT_3D('',#1782,#1464,#1465); +#1174=AXIS2_PLACEMENT_3D('',#1786,#1467,#1468); +#1175=AXIS2_PLACEMENT_3D('',#1788,#1470,#1471); +#1176=AXIS2_PLACEMENT_3D('',#1790,#1472,#1473); +#1177=AXIS2_PLACEMENT_3D('',#1792,#1475,#1476); +#1178=AXIS2_PLACEMENT_3D('',#1793,#1477,#1478); +#1179=AXIS2_PLACEMENT_3D('',#1794,#1479,#1480); +#1180=AXIS2_PLACEMENT_3D('',#1796,#1481,#1482); +#1181=AXIS2_PLACEMENT_3D('',#1798,#1484,#1485); +#1182=AXIS2_PLACEMENT_3D('',#1800,#1486,#1487); +#1183=AXIS2_PLACEMENT_3D('',#1802,#1489,#1490); +#1184=AXIS2_PLACEMENT_3D('',#1804,#1491,#1492); +#1185=AXIS2_PLACEMENT_3D('',#1806,#1494,#1495); +#1186=AXIS2_PLACEMENT_3D('',#1808,#1496,#1497); +#1187=AXIS2_PLACEMENT_3D('',#1810,#1499,#1500); +#1188=AXIS2_PLACEMENT_3D('',#1811,#1501,#1502); +#1189=AXIS2_PLACEMENT_3D('',#1812,#1503,#1504); +#1190=AXIS2_PLACEMENT_3D('',#1815,#1507,#1508); +#1191=AXIS2_PLACEMENT_3D('',#1816,#1509,#1510); +#1192=AXIS2_PLACEMENT_3D('',#1818,#1512,#1513); +#1193=AXIS2_PLACEMENT_3D('',#1819,#1514,#1515); +#1194=AXIS2_PLACEMENT_3D('',#1822,#1518,#1519); +#1195=AXIS2_PLACEMENT_3D('',#1824,#1521,#1522); +#1196=AXIS2_PLACEMENT_3D('',#1826,#1524,#1525); +#1197=AXIS2_PLACEMENT_3D('',#1827,#1526,#1527); +#1198=AXIS2_PLACEMENT_3D('',#1829,#1529,#1530); +#1199=DIRECTION('axis',(0.,0.,1.)); +#1200=DIRECTION('refdir',(1.,0.,0.)); +#1201=DIRECTION('center_axis',(-1.,0.,4.045088040451E-16)); +#1202=DIRECTION('ref_axis',(0.,1.,0.)); +#1203=DIRECTION('center_axis',(-1.,0.,6.61281535427087E-16)); +#1204=DIRECTION('ref_axis',(0.,1.,0.)); +#1205=DIRECTION('',(-1.,0.,4.045088040451E-16)); +#1206=DIRECTION('center_axis',(1.,0.,-6.61281535427087E-16)); +#1207=DIRECTION('ref_axis',(0.,1.,0.)); +#1208=DIRECTION('center_axis',(-1.,0.,4.045088040451E-16)); +#1209=DIRECTION('ref_axis',(0.,1.,0.)); +#1210=DIRECTION('center_axis',(-1.,0.,6.61281535427087E-16)); +#1211=DIRECTION('ref_axis',(0.,1.,0.)); +#1212=DIRECTION('',(-1.,0.,4.045088040451E-16)); +#1213=DIRECTION('center_axis',(1.,0.,-6.61281535427087E-16)); +#1214=DIRECTION('ref_axis',(0.,1.,0.)); +#1215=DIRECTION('center_axis',(-1.,0.,4.045088040451E-16)); +#1216=DIRECTION('ref_axis',(0.,1.,0.)); +#1217=DIRECTION('center_axis',(-1.,0.,6.61281535427087E-16)); +#1218=DIRECTION('ref_axis',(0.,1.,0.)); +#1219=DIRECTION('',(-1.,0.,4.045088040451E-16)); +#1220=DIRECTION('center_axis',(1.,0.,-6.61281535427087E-16)); +#1221=DIRECTION('ref_axis',(0.,1.,0.)); +#1222=DIRECTION('center_axis',(-1.,0.,4.045088040451E-16)); +#1223=DIRECTION('ref_axis',(0.,1.,0.)); +#1224=DIRECTION('center_axis',(-1.,0.,6.61281535427087E-16)); +#1225=DIRECTION('ref_axis',(0.,1.,0.)); +#1226=DIRECTION('',(-1.,0.,4.045088040451E-16)); +#1227=DIRECTION('center_axis',(1.,0.,-6.61281535427087E-16)); +#1228=DIRECTION('ref_axis',(0.,1.,0.)); +#1229=DIRECTION('center_axis',(-1.,0.,4.045088040451E-16)); +#1230=DIRECTION('ref_axis',(0.,1.,0.)); +#1231=DIRECTION('center_axis',(-1.,0.,6.61281535427087E-16)); +#1232=DIRECTION('ref_axis',(0.,1.,0.)); +#1233=DIRECTION('',(-1.,0.,4.045088040451E-16)); +#1234=DIRECTION('center_axis',(1.,0.,-6.61281535427087E-16)); +#1235=DIRECTION('ref_axis',(0.,1.,0.)); +#1236=DIRECTION('center_axis',(-1.,0.,4.045088040451E-16)); +#1237=DIRECTION('ref_axis',(0.,1.,0.)); +#1238=DIRECTION('center_axis',(-1.,0.,6.61281535427087E-16)); +#1239=DIRECTION('ref_axis',(0.,1.,0.)); +#1240=DIRECTION('',(-1.,0.,4.045088040451E-16)); +#1241=DIRECTION('center_axis',(1.,0.,-6.61281535427087E-16)); +#1242=DIRECTION('ref_axis',(0.,1.,0.)); +#1243=DIRECTION('center_axis',(0.,1.,1.6821560979169E-17)); +#1244=DIRECTION('ref_axis',(0.,1.6821560979169E-17,-1.)); +#1245=DIRECTION('',(-6.61281535427087E-16,1.6821560979169E-17,-1.)); +#1246=DIRECTION('',(-1.,0.,0.)); +#1247=DIRECTION('',(6.61281535427087E-16,-1.6821560979169E-17,1.)); +#1248=DIRECTION('',(-1.,0.,0.)); +#1249=DIRECTION('center_axis',(0.,0.988248846040657,-0.152853584515735)); +#1250=DIRECTION('ref_axis',(0.,-0.152853584515735,-0.988248846040657)); +#1251=DIRECTION('center_axis',(0.,-0.988248846040657,0.152853584515735)); +#1252=DIRECTION('ref_axis',(-1.28575385500029E-16,-0.152853584515735,-0.988248846040657)); +#1253=DIRECTION('center_axis',(0.,0.988248846040657,-0.152853584515735)); +#1254=DIRECTION('ref_axis',(5.27488761025759E-16,-0.152853584515735,-0.988248846040657)); +#1255=DIRECTION('',(-0.495573879747861,0.132763394226749,0.858359138627326)); +#1256=DIRECTION('center_axis',(0.,-0.988248846040657,0.152853584515735)); +#1257=DIRECTION('ref_axis',(-1.24289539316695E-15,0.152853584515735,0.988248846040658)); +#1258=DIRECTION('',(0.,0.152853584515735,0.988248846040657)); +#1259=DIRECTION('',(-1.,0.,0.)); +#1260=DIRECTION('',(0.,-0.152853584515735,-0.988248846040657)); +#1261=DIRECTION('center_axis',(0.,0.988248846040657,-0.152853584515735)); +#1262=DIRECTION('ref_axis',(-1.26597302646182E-15,0.152853584515735,0.988248846040657)); +#1263=DIRECTION('',(0.495573879747861,-0.132763394226749,-0.858359138627326)); +#1264=DIRECTION('center_axis',(-1.,0.,0.)); +#1265=DIRECTION('ref_axis',(0.,0.,-1.)); +#1266=DIRECTION('center_axis',(-1.,0.,0.)); +#1267=DIRECTION('ref_axis',(0.,0.,-1.)); +#1268=DIRECTION('',(-1.,0.,0.)); +#1269=DIRECTION('center_axis',(1.,0.,0.)); +#1270=DIRECTION('ref_axis',(0.,0.,-1.)); +#1271=DIRECTION('',(1.,0.,0.)); +#1272=DIRECTION('center_axis',(0.,0.988248846040658,0.152853584515734)); +#1273=DIRECTION('ref_axis',(0.,0.152853584515734,-0.988248846040658)); +#1274=DIRECTION('center_axis',(0.,-0.988248846040658,-0.152853584515734)); +#1275=DIRECTION('ref_axis',(3.42867694666745E-16,-0.152853584515734,0.988248846040658)); +#1276=DIRECTION('',(-0.495573879747861,0.132763394226748,-0.858359138627326)); +#1277=DIRECTION('center_axis',(0.,0.988248846040658,0.152853584515734)); +#1278=DIRECTION('ref_axis',(-8.43982017641215E-16,0.152853584515734,-0.988248846040658)); +#1279=DIRECTION('',(0.,0.152853584515734,-0.988248846040658)); +#1280=DIRECTION('',(0.,-0.152853584515734,0.988248846040658)); +#1281=DIRECTION('center_axis',(0.,-0.988248846040658,-0.152853584515734)); +#1282=DIRECTION('ref_axis',(-1.71433847333372E-16,0.152853584515734,-0.988248846040658)); +#1283=DIRECTION('',(0.495573879747861,-0.132763394226748,0.858359138627326)); +#1284=DIRECTION('center_axis',(0.,0.988248846040658,0.152853584515734)); +#1285=DIRECTION('ref_axis',(1.47696853087213E-15,-0.152853584515734,0.988248846040658)); +#1286=DIRECTION('center_axis',(0.,-0.988248846040657,0.152853584515735)); +#1287=DIRECTION('ref_axis',(0.,0.152853584515735,0.988248846040657)); +#1288=DIRECTION('center_axis',(0.,0.988248846040657,-0.152853584515735)); +#1289=DIRECTION('ref_axis',(1.02860308400024E-15,0.152853584515735,0.988248846040657)); +#1290=DIRECTION('',(-1.,0.,0.)); +#1291=DIRECTION('center_axis',(0.,-0.988248846040657,0.152853584515735)); +#1292=DIRECTION('ref_axis',(1.95170841579531E-15,0.152853584515735,0.988248846040657)); +#1293=DIRECTION('',(-0.495573879747861,-0.132763394226749,-0.858359138627326)); +#1294=DIRECTION('center_axis',(0.,0.988248846040657,-0.152853584515735)); +#1295=DIRECTION('ref_axis',(4.28584618333429E-16,-0.152853584515735,-0.988248846040657)); +#1296=DIRECTION('',(0.,-0.152853584515735,-0.988248846040657)); +#1297=DIRECTION('',(-1.,0.,0.)); +#1298=DIRECTION('',(0.,0.152853584515735,0.988248846040657)); +#1299=DIRECTION('center_axis',(0.,-0.988248846040657,0.152853584515735)); +#1300=DIRECTION('ref_axis',(2.6374438051288E-16,-0.152853584515735,-0.988248846040657)); +#1301=DIRECTION('',(0.495573879747861,0.132763394226749,0.858359138627326)); +#1302=DIRECTION('center_axis',(0.,-1.,8.41078048958452E-18)); +#1303=DIRECTION('ref_axis',(0.,8.41078048958452E-18,1.)); +#1304=DIRECTION('',(6.61281535427087E-16,8.41078048958452E-18,1.)); +#1305=DIRECTION('',(-1.,0.,0.)); +#1306=DIRECTION('',(-6.61281535427087E-16,-8.41078048958452E-18,-1.)); +#1307=DIRECTION('center_axis',(0.,-0.988248846040657,-0.152853584515735)); +#1308=DIRECTION('ref_axis',(0.,-0.152853584515735,0.988248846040658)); +#1309=DIRECTION('center_axis',(0.,0.988248846040657,0.152853584515735)); +#1310=DIRECTION('ref_axis',(-3.42867694666745E-16,0.152853584515735,-0.988248846040657)); +#1311=DIRECTION('',(-0.495573879747861,-0.132763394226749,0.858359138627326)); +#1312=DIRECTION('center_axis',(0.,-0.988248846040657,-0.152853584515735)); +#1313=DIRECTION('ref_axis',(9.49479769846367E-16,-0.152853584515735,0.988248846040657)); +#1314=DIRECTION('',(0.,-0.152853584515735,0.988248846040658)); +#1315=DIRECTION('',(-1.,0.,0.)); +#1316=DIRECTION('',(0.,0.152853584515735,-0.988248846040658)); +#1317=DIRECTION('center_axis',(0.,0.988248846040657,0.152853584515735)); +#1318=DIRECTION('ref_axis',(-1.24289539316695E-15,-0.152853584515735,0.988248846040658)); +#1319=DIRECTION('',(0.495573879747861,0.132763394226749,-0.858359138627326)); +#1320=DIRECTION('center_axis',(0.,-0.988248846040657,-0.152853584515735)); +#1321=DIRECTION('ref_axis',(5.27488761025759E-16,0.152853584515735,-0.988248846040657)); +#1322=DIRECTION('center_axis',(-0.866025403784439,0.,-0.499999999999999)); +#1323=DIRECTION('ref_axis',(-0.499999999999999,0.,0.866025403784439)); +#1324=DIRECTION('',(0.,-1.,0.)); +#1325=DIRECTION('',(0.,1.,0.)); +#1326=DIRECTION('center_axis',(0.,1.,0.)); +#1327=DIRECTION('ref_axis',(-0.965925826289067,0.,-0.258819045102526)); +#1328=DIRECTION('',(0.,-1.,0.)); +#1329=DIRECTION('center_axis',(-1.,0.,6.61281535427087E-16)); +#1330=DIRECTION('ref_axis',(6.61281535427087E-16,0.,1.)); +#1331=DIRECTION('',(0.,1.,0.)); +#1332=DIRECTION('center_axis',(0.,1.,0.)); +#1333=DIRECTION('ref_axis',(0.96592582628903,0.,0.258819045102662)); +#1334=DIRECTION('',(0.,1.,0.)); +#1335=DIRECTION('center_axis',(0.,1.,0.)); +#1336=DIRECTION('ref_axis',(-0.965925826289069,0.,0.258819045102519)); +#1337=DIRECTION('',(0.,-1.,0.)); +#1338=DIRECTION('center_axis',(-1.,0.,0.)); +#1339=DIRECTION('ref_axis',(0.,0.,1.)); +#1340=DIRECTION('center_axis',(1.,0.,0.)); +#1341=DIRECTION('ref_axis',(0.,0.,-1.)); +#1342=DIRECTION('center_axis',(1.,0.,0.)); +#1343=DIRECTION('ref_axis',(0.,0.,-1.)); +#1344=DIRECTION('center_axis',(1.,0.,0.)); +#1345=DIRECTION('ref_axis',(0.,0.,-1.)); +#1346=DIRECTION('center_axis',(1.,0.,0.)); +#1347=DIRECTION('ref_axis',(0.,0.,-1.)); +#1348=DIRECTION('center_axis',(1.,0.,0.)); +#1349=DIRECTION('ref_axis',(0.,0.,-1.)); +#1350=DIRECTION('center_axis',(-1.,0.,0.)); +#1351=DIRECTION('ref_axis',(0.,1.,0.)); +#1352=DIRECTION('center_axis',(-1.,0.,0.)); +#1353=DIRECTION('ref_axis',(0.,1.,0.)); +#1354=DIRECTION('center_axis',(-1.,0.,0.)); +#1355=DIRECTION('ref_axis',(0.,1.,0.)); +#1356=DIRECTION('center_axis',(-1.,0.,0.)); +#1357=DIRECTION('ref_axis',(0.,1.,0.)); +#1358=DIRECTION('center_axis',(-1.,0.,0.)); +#1359=DIRECTION('ref_axis',(0.,1.,0.)); +#1360=DIRECTION('center_axis',(-1.,0.,0.)); +#1361=DIRECTION('ref_axis',(0.,0.,1.)); +#1362=DIRECTION('',(0.,0.,-1.)); +#1363=DIRECTION('center_axis',(-1.,0.,0.)); +#1364=DIRECTION('ref_axis',(0.,0.,-1.)); +#1365=DIRECTION('center_axis',(-1.,0.,0.)); +#1366=DIRECTION('ref_axis',(0.,0.,-1.)); +#1367=DIRECTION('center_axis',(1.,0.,0.)); +#1368=DIRECTION('ref_axis',(0.,0.,-1.)); +#1369=DIRECTION('center_axis',(1.,0.,0.)); +#1370=DIRECTION('ref_axis',(0.,0.,-1.)); +#1371=DIRECTION('center_axis',(1.,0.,0.)); +#1372=DIRECTION('ref_axis',(0.,0.,-1.)); +#1373=DIRECTION('center_axis',(-1.,0.,0.)); +#1374=DIRECTION('ref_axis',(0.,0.,-1.)); +#1375=DIRECTION('center_axis',(-1.,0.,0.)); +#1376=DIRECTION('ref_axis',(0.,0.,-1.)); +#1377=DIRECTION('',(0.,-1.,0.)); +#1378=DIRECTION('center_axis',(1.,0.,0.)); +#1379=DIRECTION('ref_axis',(0.,1.,0.)); +#1380=DIRECTION('center_axis',(1.,0.,0.)); +#1381=DIRECTION('ref_axis',(0.,1.,0.)); +#1382=DIRECTION('center_axis',(1.,0.,0.)); +#1383=DIRECTION('ref_axis',(0.,1.,0.)); +#1384=DIRECTION('center_axis',(1.,0.,0.)); +#1385=DIRECTION('ref_axis',(0.,1.,0.)); +#1386=DIRECTION('center_axis',(1.,0.,0.)); +#1387=DIRECTION('ref_axis',(0.,1.,0.)); +#1388=DIRECTION('center_axis',(0.,1.,0.)); +#1389=DIRECTION('ref_axis',(0.96592582628907,0.,-0.258819045102515)); +#1390=DIRECTION('',(0.,1.,0.)); +#1391=DIRECTION('center_axis',(-0.866025403784439,0.,0.5)); +#1392=DIRECTION('ref_axis',(0.5,0.,0.866025403784439)); +#1393=DIRECTION('',(0.,-1.,0.)); +#1394=DIRECTION('center_axis',(-1.,0.,0.)); +#1395=DIRECTION('ref_axis',(0.,1.,0.)); +#1396=DIRECTION('',(-1.,0.,0.)); +#1397=DIRECTION('center_axis',(1.,0.,0.)); +#1398=DIRECTION('ref_axis',(0.,1.,0.)); +#1399=DIRECTION('center_axis',(-1.,0.,0.)); +#1400=DIRECTION('ref_axis',(0.,1.,0.)); +#1401=DIRECTION('',(-1.,0.,0.)); +#1402=DIRECTION('center_axis',(1.,0.,0.)); +#1403=DIRECTION('ref_axis',(0.,1.,0.)); +#1404=DIRECTION('center_axis',(-1.,0.,0.)); +#1405=DIRECTION('ref_axis',(0.,1.,0.)); +#1406=DIRECTION('center_axis',(-1.,0.,0.)); +#1407=DIRECTION('ref_axis',(0.,1.,0.)); +#1408=DIRECTION('',(-1.,0.,0.)); +#1409=DIRECTION('center_axis',(-1.,0.,0.)); +#1410=DIRECTION('ref_axis',(0.,1.,0.)); +#1411=DIRECTION('center_axis',(-1.,0.,0.)); +#1412=DIRECTION('ref_axis',(0.,1.,0.)); +#1413=DIRECTION('',(-1.,0.,0.)); +#1414=DIRECTION('center_axis',(-1.,0.,0.)); +#1415=DIRECTION('ref_axis',(0.,1.,0.)); +#1416=DIRECTION('center_axis',(-1.,0.,0.)); +#1417=DIRECTION('ref_axis',(0.,1.,0.)); +#1418=DIRECTION('',(-1.,0.,0.)); +#1419=DIRECTION('center_axis',(-1.,0.,0.)); +#1420=DIRECTION('ref_axis',(0.,1.,0.)); +#1421=DIRECTION('center_axis',(-1.,0.,0.)); +#1422=DIRECTION('ref_axis',(0.,1.,0.)); +#1423=DIRECTION('',(-1.,0.,0.)); +#1424=DIRECTION('center_axis',(-1.,0.,0.)); +#1425=DIRECTION('ref_axis',(0.,1.,0.)); +#1426=DIRECTION('center_axis',(-1.,0.,0.)); +#1427=DIRECTION('ref_axis',(0.,1.,0.)); +#1428=DIRECTION('',(-1.,0.,0.)); +#1429=DIRECTION('center_axis',(-1.,0.,0.)); +#1430=DIRECTION('ref_axis',(0.,1.,0.)); +#1431=DIRECTION('',(-1.,0.,0.)); +#1432=DIRECTION('center_axis',(1.,0.,0.)); +#1433=DIRECTION('ref_axis',(0.,1.,0.)); +#1434=DIRECTION('center_axis',(-1.,0.,0.)); +#1435=DIRECTION('ref_axis',(0.,1.,0.)); +#1436=DIRECTION('',(-1.,0.,0.)); +#1437=DIRECTION('center_axis',(1.,0.,0.)); +#1438=DIRECTION('ref_axis',(0.,1.,0.)); +#1439=DIRECTION('center_axis',(-1.,0.,0.)); +#1440=DIRECTION('ref_axis',(0.,1.,0.)); +#1441=DIRECTION('',(-1.,0.,0.)); +#1442=DIRECTION('center_axis',(1.,0.,0.)); +#1443=DIRECTION('ref_axis',(0.,1.,0.)); +#1444=DIRECTION('center_axis',(-1.,0.,0.)); +#1445=DIRECTION('ref_axis',(0.,0.,-1.)); +#1446=DIRECTION('',(-1.,0.,0.)); +#1447=DIRECTION('center_axis',(1.,0.,0.)); +#1448=DIRECTION('ref_axis',(0.,0.,-1.)); +#1449=DIRECTION('',(-1.,0.,0.)); +#1450=DIRECTION('center_axis',(-1.,0.,0.)); +#1451=DIRECTION('ref_axis',(0.,0.,-1.)); +#1452=DIRECTION('center_axis',(1.,0.,0.)); +#1453=DIRECTION('ref_axis',(0.,0.,-1.)); +#1454=DIRECTION('',(-1.,0.,0.)); +#1455=DIRECTION('center_axis',(-1.,0.,0.)); +#1456=DIRECTION('ref_axis',(0.,-0.5,0.866025403784438)); +#1457=DIRECTION('center_axis',(1.,0.,0.)); +#1458=DIRECTION('ref_axis',(0.,0.,-1.)); +#1459=DIRECTION('',(-1.,0.,0.)); +#1460=DIRECTION('center_axis',(-1.,0.,0.)); +#1461=DIRECTION('ref_axis',(0.,0.,-1.)); +#1462=DIRECTION('center_axis',(1.,0.,0.)); +#1463=DIRECTION('ref_axis',(0.,0.,-1.)); +#1464=DIRECTION('center_axis',(-1.,0.,0.)); +#1465=DIRECTION('ref_axis',(0.,0.,-1.)); +#1466=DIRECTION('',(-1.,0.,0.)); +#1467=DIRECTION('center_axis',(1.,0.,0.)); +#1468=DIRECTION('ref_axis',(0.,0.,-1.)); +#1469=DIRECTION('',(-1.,0.,0.)); +#1470=DIRECTION('center_axis',(-1.,0.,0.)); +#1471=DIRECTION('ref_axis',(0.,0.499999999999999,0.866025403784439)); +#1472=DIRECTION('center_axis',(1.,0.,0.)); +#1473=DIRECTION('ref_axis',(0.,0.,-1.)); +#1474=DIRECTION('',(-1.,0.,0.)); +#1475=DIRECTION('center_axis',(-1.,0.,0.)); +#1476=DIRECTION('ref_axis',(0.,0.,-1.)); +#1477=DIRECTION('center_axis',(1.,0.,0.)); +#1478=DIRECTION('ref_axis',(0.,0.,-1.)); +#1479=DIRECTION('center_axis',(-1.,0.,0.)); +#1480=DIRECTION('ref_axis',(0.,0.,-1.)); +#1481=DIRECTION('center_axis',(-1.,0.,0.)); +#1482=DIRECTION('ref_axis',(0.,0.,-1.)); +#1483=DIRECTION('',(-1.,0.,0.)); +#1484=DIRECTION('center_axis',(-1.,0.,0.)); +#1485=DIRECTION('ref_axis',(0.,0.,-1.)); +#1486=DIRECTION('center_axis',(-1.,0.,0.)); +#1487=DIRECTION('ref_axis',(0.,0.,-1.)); +#1488=DIRECTION('',(-1.,0.,0.)); +#1489=DIRECTION('center_axis',(-1.,0.,0.)); +#1490=DIRECTION('ref_axis',(0.,-1.22464679914735E-16,1.)); +#1491=DIRECTION('center_axis',(1.,0.,0.)); +#1492=DIRECTION('ref_axis',(0.,0.,-1.)); +#1493=DIRECTION('',(-1.,0.,0.)); +#1494=DIRECTION('center_axis',(-1.,0.,0.)); +#1495=DIRECTION('ref_axis',(0.,0.,-1.)); +#1496=DIRECTION('center_axis',(-1.,0.,0.)); +#1497=DIRECTION('ref_axis',(0.,0.,-1.)); +#1498=DIRECTION('',(-1.,0.,0.)); +#1499=DIRECTION('center_axis',(-1.,0.,0.)); +#1500=DIRECTION('ref_axis',(0.,0.,-1.)); +#1501=DIRECTION('center_axis',(-1.,0.,0.)); +#1502=DIRECTION('ref_axis',(0.,0.,-1.)); +#1503=DIRECTION('center_axis',(-1.,0.,0.)); +#1504=DIRECTION('ref_axis',(0.,0.,1.)); +#1505=DIRECTION('',(0.,-1.,0.)); +#1506=DIRECTION('',(0.,0.,-1.)); +#1507=DIRECTION('center_axis',(0.,1.,0.)); +#1508=DIRECTION('ref_axis',(0.,0.,1.)); +#1509=DIRECTION('center_axis',(-0.866025403784439,0.,0.5)); +#1510=DIRECTION('ref_axis',(0.5,0.,0.866025403784439)); +#1511=DIRECTION('',(0.,1.,0.)); +#1512=DIRECTION('center_axis',(0.,1.,0.)); +#1513=DIRECTION('ref_axis',(0.96592582628907,0.,-0.258819045102515)); +#1514=DIRECTION('center_axis',(0.,1.,0.)); +#1515=DIRECTION('ref_axis',(-0.965925826289067,0.,-0.258819045102526)); +#1516=DIRECTION('',(0.,-1.,0.)); +#1517=DIRECTION('',(0.,1.,0.)); +#1518=DIRECTION('center_axis',(-1.,0.,6.61281535427087E-16)); +#1519=DIRECTION('ref_axis',(6.61281535427087E-16,0.,1.)); +#1520=DIRECTION('',(0.,1.,0.)); +#1521=DIRECTION('center_axis',(-0.866025403784439,0.,-0.499999999999999)); +#1522=DIRECTION('ref_axis',(-0.499999999999999,0.,0.866025403784439)); +#1523=DIRECTION('',(0.,-1.,0.)); +#1524=DIRECTION('center_axis',(0.,1.,0.)); +#1525=DIRECTION('ref_axis',(-0.965925826289069,0.,0.258819045102519)); +#1526=DIRECTION('center_axis',(0.,1.,0.)); +#1527=DIRECTION('ref_axis',(0.96592582628903,0.,0.258819045102662)); +#1528=DIRECTION('',(0.,1.,0.)); +#1529=DIRECTION('center_axis',(-1.,0.,0.)); +#1530=DIRECTION('ref_axis',(0.,0.,1.)); +#1531=CARTESIAN_POINT('',(0.,0.,0.)); +#1532=CARTESIAN_POINT('Origin',(-15.7499999999999,-15.0000000000002,-132.)); +#1533=CARTESIAN_POINT('',(-10.75,-16.6000000000002,-132.)); +#1534=CARTESIAN_POINT('Origin',(-10.75,-15.0000000000002,-132.)); +#1535=CARTESIAN_POINT('',(-13.25,-16.6000000000002,-132.)); +#1536=CARTESIAN_POINT('',(-15.7499999999999,-16.6000000000002,-132.)); +#1537=CARTESIAN_POINT('Origin',(-13.25,-15.0000000000002,-132.)); +#1538=CARTESIAN_POINT('Origin',(-15.75,15.,-196.853658899391)); +#1539=CARTESIAN_POINT('',(-10.75,13.4,-196.853658899391)); +#1540=CARTESIAN_POINT('Origin',(-10.75,15.,-196.853658899391)); +#1541=CARTESIAN_POINT('',(-13.25,13.4,-196.853658899391)); +#1542=CARTESIAN_POINT('',(-15.75,13.4,-196.853658899391)); +#1543=CARTESIAN_POINT('Origin',(-13.25,15.,-196.853658899391)); +#1544=CARTESIAN_POINT('Origin',(-15.7499999999999,15.,-67.1463411006086)); +#1545=CARTESIAN_POINT('',(-10.75,13.4,-67.1463411006086)); +#1546=CARTESIAN_POINT('Origin',(-10.75,15.,-67.1463411006086)); +#1547=CARTESIAN_POINT('',(-13.25,13.4,-67.1463411006086)); +#1548=CARTESIAN_POINT('',(-15.7499999999999,13.4,-67.1463411006086)); +#1549=CARTESIAN_POINT('Origin',(-13.25,15.,-67.1463411006086)); +#1550=CARTESIAN_POINT('Origin',(-15.7499999999999,15.0000000000074,-132.)); +#1551=CARTESIAN_POINT('',(-10.75,13.4000000000074,-132.)); +#1552=CARTESIAN_POINT('Origin',(-10.75,15.0000000000074,-132.)); +#1553=CARTESIAN_POINT('',(-13.25,13.4000000000074,-132.)); +#1554=CARTESIAN_POINT('',(-15.7499999999999,13.4000000000074,-132.)); +#1555=CARTESIAN_POINT('Origin',(-13.25,15.0000000000074,-132.)); +#1556=CARTESIAN_POINT('Origin',(-15.75,-15.,-196.853658899391)); +#1557=CARTESIAN_POINT('',(-10.75,-16.6,-196.853658899391)); +#1558=CARTESIAN_POINT('Origin',(-10.75,-15.,-196.853658899391)); +#1559=CARTESIAN_POINT('',(-13.25,-16.6,-196.853658899391)); +#1560=CARTESIAN_POINT('',(-15.75,-16.6,-196.853658899391)); +#1561=CARTESIAN_POINT('Origin',(-13.25,-15.,-196.853658899391)); +#1562=CARTESIAN_POINT('Origin',(-15.7499999999999,-15.,-67.1463411006086)); +#1563=CARTESIAN_POINT('',(-10.75,-16.6,-67.1463411006086)); +#1564=CARTESIAN_POINT('Origin',(-10.75,-15.,-67.1463411006086)); +#1565=CARTESIAN_POINT('',(-13.25,-16.6,-67.1463411006086)); +#1566=CARTESIAN_POINT('',(-15.7499999999999,-16.6,-67.1463411006086)); +#1567=CARTESIAN_POINT('Origin',(-13.25,-15.,-67.1463411006086)); +#1568=CARTESIAN_POINT('Origin',(2.5,-20.,-57.1463411006086)); +#1569=CARTESIAN_POINT('',(-10.7499999999999,-20.,-57.1463411006086)); +#1570=CARTESIAN_POINT('',(-10.75,-20.,-206.853658899391)); +#1571=CARTESIAN_POINT('',(-10.75,-20.,-132.34833395016)); +#1572=CARTESIAN_POINT('',(-13.2499999999999,-20.,-57.1463411006086)); +#1573=CARTESIAN_POINT('',(2.5,-20.,-57.1463411006086)); +#1574=CARTESIAN_POINT('',(-13.25,-20.,-206.853658899391)); +#1575=CARTESIAN_POINT('',(-13.25,-20.,-132.34833395016)); +#1576=CARTESIAN_POINT('',(2.5,-20.,-206.853658899391)); +#1577=CARTESIAN_POINT('Origin',(2.5,-20.,-206.853658899391)); +#1578=CARTESIAN_POINT('',(-10.7366025403785,-20.00773355745,-206.903658899391)); +#1579=CARTESIAN_POINT('Origin',(-10.65,-20.,-206.853658899391)); +#1580=CARTESIAN_POINT('',(-12.9016660498395,-20.2010724937009,-208.153658899391)); +#1581=CARTESIAN_POINT('Origin',(-10.65,-20.,-206.853658899391)); +#1582=CARTESIAN_POINT('',(-0.0133974596215698,-23.6538175911905,-230.476794919243)); +#1583=CARTESIAN_POINT('',(-5.62092918878432,-22.1515694380461,-220.764265059279)); +#1584=CARTESIAN_POINT('',(0.,-23.6615511486406,-230.526794919243)); +#1585=CARTESIAN_POINT('Origin',(-0.1,-23.6615511486406,-230.526794919243)); +#1586=CARTESIAN_POINT('',(0.,-28.1650921121588,-259.643672841302)); +#1587=CARTESIAN_POINT('',(0.,-25.5931198411879,-243.015023687353)); +#1588=CARTESIAN_POINT('',(2.5,-28.1650921121588,-259.643672841302)); +#1589=CARTESIAN_POINT('',(2.5,-28.1650921121588,-259.643672841302)); +#1590=CARTESIAN_POINT('',(2.5,-23.6615511486406,-230.526794919243)); +#1591=CARTESIAN_POINT('',(2.5,-25.5931198411879,-243.015023687353)); +#1592=CARTESIAN_POINT('',(2.15166604983953,-23.4604786549397,-229.226794919243)); +#1593=CARTESIAN_POINT('Origin',(-0.1,-23.6615511486406,-230.526794919243)); +#1594=CARTESIAN_POINT('',(-3.44314512374714,-21.9616383168633,-219.536297707837)); +#1595=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1596=CARTESIAN_POINT('',(0.,-28.1650921121588,-4.35632715869845)); +#1597=CARTESIAN_POINT('',(0.,-28.5,5.23536506635494E-15)); +#1598=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1599=CARTESIAN_POINT('',(2.5,-28.1650921121588,-4.35632715869845)); +#1600=CARTESIAN_POINT('',(2.5,-28.1650921121588,-4.35632715869845)); +#1601=CARTESIAN_POINT('',(2.5,-28.5,5.23536506635494E-15)); +#1602=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1603=CARTESIAN_POINT('',(2.5,-28.5,0.)); +#1604=CARTESIAN_POINT('Origin',(2.5,-28.1650921121588,-4.35632715869845)); +#1605=CARTESIAN_POINT('',(-10.7366025403784,-20.0077335574501,-57.0963411006084)); +#1606=CARTESIAN_POINT('Origin',(-10.6499999999999,-20.0000000000001,-57.1463411006084)); +#1607=CARTESIAN_POINT('',(2.15166604983954,-23.4604786549397,-34.7732050807569)); +#1608=CARTESIAN_POINT('',(1.54515302918986,-23.2979948547339,-35.8237164479742)); +#1609=CARTESIAN_POINT('',(2.5,-23.6615511486406,-33.4732050807569)); +#1610=CARTESIAN_POINT('Origin',(-0.1,-23.6615511486406,-33.4732050807569)); +#1611=CARTESIAN_POINT('',(2.5,-28.1650921121588,-4.35632715869844)); +#1612=CARTESIAN_POINT('',(0.,-23.6615511486406,-33.4732050807569)); +#1613=CARTESIAN_POINT('',(0.,-28.1650921121588,-4.35632715869844)); +#1614=CARTESIAN_POINT('',(-0.0133974596215561,-23.6538175911906,-33.5232050807569)); +#1615=CARTESIAN_POINT('Origin',(-0.1,-23.6615511486406,-33.4732050807569)); +#1616=CARTESIAN_POINT('',(-12.9016660498395,-20.201072493701,-55.8463411006084)); +#1617=CARTESIAN_POINT('',(-0.632631035847312,-23.4879259759167,-34.5957490965325)); +#1618=CARTESIAN_POINT('Origin',(-10.6499999999999,-20.0000000000001,-57.1463411006084)); +#1619=CARTESIAN_POINT('Origin',(2.5,20.,-57.1463411006086)); +#1620=CARTESIAN_POINT('',(-10.7499999999999,20.,-57.1463411006086)); +#1621=CARTESIAN_POINT('',(-10.7366025403784,20.00773355745,-57.0963411006084)); +#1622=CARTESIAN_POINT('Origin',(-10.6499999999999,20.,-57.1463411006084)); +#1623=CARTESIAN_POINT('',(-13.2499999999999,20.,-57.1463411006086)); +#1624=CARTESIAN_POINT('',(2.5,20.,-57.1463411006086)); +#1625=CARTESIAN_POINT('',(-12.9016660498395,20.2010724937009,-55.8463411006084)); +#1626=CARTESIAN_POINT('Origin',(-10.6499999999999,20.,-57.1463411006084)); +#1627=CARTESIAN_POINT('',(-0.0133974596215561,23.6538175911905,-33.5232050807569)); +#1628=CARTESIAN_POINT('',(-12.1291561514255,20.4080265733618,-54.5083147072055)); +#1629=CARTESIAN_POINT('',(0.,23.6615511486405,-33.4732050807569)); +#1630=CARTESIAN_POINT('Origin',(-0.1,23.6615511486405,-33.4732050807569)); +#1631=CARTESIAN_POINT('',(0.,28.1650921121588,-4.35632715869845)); +#1632=CARTESIAN_POINT('',(0.,24.0825460560794,-30.7513341296535)); +#1633=CARTESIAN_POINT('',(2.5,28.1650921121588,-4.35632715869845)); +#1634=CARTESIAN_POINT('',(2.5,28.1650921121588,-4.35632715869845)); +#1635=CARTESIAN_POINT('',(2.5,23.6615511486405,-33.4732050807569)); +#1636=CARTESIAN_POINT('',(2.5,24.0825460560794,-30.7513341296535)); +#1637=CARTESIAN_POINT('',(2.15166604983954,23.4604786549396,-34.7732050807569)); +#1638=CARTESIAN_POINT('Origin',(-0.1,23.6615511486405,-33.4732050807569)); +#1639=CARTESIAN_POINT('',(-9.95137208638832,20.2180954521789,-55.7362820586473)); +#1640=CARTESIAN_POINT('Origin',(2.5,20.,-206.853658899391)); +#1641=CARTESIAN_POINT('',(-10.75,20.,-206.853658899391)); +#1642=CARTESIAN_POINT('',(-10.75,20.,-207.201992849552)); +#1643=CARTESIAN_POINT('',(-13.25,20.,-206.853658899391)); +#1644=CARTESIAN_POINT('',(2.5,20.,-206.853658899391)); +#1645=CARTESIAN_POINT('',(-13.25,20.,-207.201992849552)); +#1646=CARTESIAN_POINT('Origin',(2.5,28.1650921121587,-259.643672841302)); +#1647=CARTESIAN_POINT('',(-10.7366025403785,20.00773355745,-206.903658899391)); +#1648=CARTESIAN_POINT('Origin',(-10.65,20.,-206.853658899391)); +#1649=CARTESIAN_POINT('',(2.15166604983953,23.4604786549396,-229.226794919243)); +#1650=CARTESIAN_POINT('',(8.05337999183103,25.0415377194181,-239.44886331851)); +#1651=CARTESIAN_POINT('',(2.5,23.6615511486406,-230.526794919243)); +#1652=CARTESIAN_POINT('Origin',(-0.1,23.6615511486406,-230.526794919243)); +#1653=CARTESIAN_POINT('',(2.5,28.1650921121587,-259.643672841302)); +#1654=CARTESIAN_POINT('',(2.5,29.6756658972673,-269.410030658308)); +#1655=CARTESIAN_POINT('',(0.,28.1650921121587,-259.643672841302)); +#1656=CARTESIAN_POINT('',(2.5,28.1650921121587,-259.643672841302)); +#1657=CARTESIAN_POINT('',(0.,23.6615511486406,-230.526794919243)); +#1658=CARTESIAN_POINT('',(0.,29.6756658972673,-269.410030658308)); +#1659=CARTESIAN_POINT('',(-0.0133974596215698,23.6538175911905,-230.476794919243)); +#1660=CARTESIAN_POINT('Origin',(-0.1,23.6615511486406,-230.526794919243)); +#1661=CARTESIAN_POINT('',(-12.9016660498395,20.2010724937009,-208.153658899391)); +#1662=CARTESIAN_POINT('',(5.87559592679385,25.2314688406009,-240.676830669952)); +#1663=CARTESIAN_POINT('Origin',(-10.65,20.,-206.853658899391)); +#1664=CARTESIAN_POINT('Origin',(2.1650635094611,0.,-229.25)); +#1665=CARTESIAN_POINT('',(2.15166604983953,0.,-229.226794919243)); +#1666=CARTESIAN_POINT('',(-10.7366025403785,0.,-206.903658899391)); +#1667=CARTESIAN_POINT('Origin',(-10.65,0.,-206.853658899391)); +#1668=CARTESIAN_POINT('',(-10.75,0.,-206.853658899391)); +#1669=CARTESIAN_POINT('Origin',(-10.75,0.,-207.550326799712)); +#1670=CARTESIAN_POINT('',(-10.7499999999999,0.,-57.1463411006084)); +#1671=CARTESIAN_POINT('Origin',(-0.1,0.,-230.526794919243)); +#1672=CARTESIAN_POINT('',(2.5,0.,-230.526794919243)); +#1673=CARTESIAN_POINT('Origin',(-10.6499999999999,0.,-57.1463411006084)); +#1674=CARTESIAN_POINT('',(-10.7366025403784,0.,-57.0963411006084)); +#1675=CARTESIAN_POINT('Origin',(2.5,0.,-284.)); +#1676=CARTESIAN_POINT('',(2.5,-24.6817240078565,-278.25)); +#1677=CARTESIAN_POINT('Origin',(2.5,0.,-264.)); +#1678=CARTESIAN_POINT('',(2.5,-18.6195461813654,-274.75)); +#1679=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,-276.5)); +#1680=CARTESIAN_POINT('',(2.5,18.6195461813654,-274.75)); +#1681=CARTESIAN_POINT('Origin',(2.5,0.,-264.)); +#1682=CARTESIAN_POINT('',(2.5,24.6817240078565,-278.25)); +#1683=CARTESIAN_POINT('Origin',(2.5,21.650635094611,-276.5)); +#1684=CARTESIAN_POINT('Origin',(2.5,0.,-264.)); +#1685=CARTESIAN_POINT('',(2.5,20.050635094611,-276.5)); +#1686=CARTESIAN_POINT('Origin',(2.5,21.650635094611,-276.5)); +#1687=CARTESIAN_POINT('',(2.5,-1.59999999999999,-239.)); +#1688=CARTESIAN_POINT('Origin',(2.5,7.36484746826356E-15,-239.)); +#1689=CARTESIAN_POINT('',(2.5,-23.250635094611,-276.5)); +#1690=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,-276.5)); +#1691=CARTESIAN_POINT('',(2.5,-23.250635094611,-251.5)); +#1692=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,-251.5)); +#1693=CARTESIAN_POINT('',(2.5,20.050635094611,-251.5)); +#1694=CARTESIAN_POINT('Origin',(2.5,21.650635094611,-251.5)); +#1695=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1696=CARTESIAN_POINT('',(0.,-28.5,0.0014077834583465)); +#1697=CARTESIAN_POINT('',(0.,-28.5,0.)); +#1698=CARTESIAN_POINT('',(0.,-24.6817240078565,14.25)); +#1699=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1700=CARTESIAN_POINT('',(0.,-18.6195461813654,10.75)); +#1701=CARTESIAN_POINT('Origin',(0.,-21.650635094611,12.5)); +#1702=CARTESIAN_POINT('',(0.,-21.4999998617311,-0.00243835255454935)); +#1703=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1704=CARTESIAN_POINT('',(0.,21.5,6.42939637984833E-16)); +#1705=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1706=CARTESIAN_POINT('',(0.,18.6195461813654,10.75)); +#1707=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1708=CARTESIAN_POINT('',(0.,24.6817240078565,14.25)); +#1709=CARTESIAN_POINT('Origin',(0.,21.650635094611,12.5)); +#1710=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1711=CARTESIAN_POINT('',(0.,0.,-33.4732050807569)); +#1712=CARTESIAN_POINT('',(0.,-23.250635094611,-12.5)); +#1713=CARTESIAN_POINT('Origin',(0.,-21.650635094611,-12.5)); +#1714=CARTESIAN_POINT('',(0.,20.050635094611,-12.5)); +#1715=CARTESIAN_POINT('Origin',(0.,21.650635094611,-12.5)); +#1716=CARTESIAN_POINT('',(0.,20.050635094611,12.5)); +#1717=CARTESIAN_POINT('Origin',(0.,21.650635094611,12.5)); +#1718=CARTESIAN_POINT('',(0.,-1.59999999999999,-25.)); +#1719=CARTESIAN_POINT('Origin',(0.,7.36484746826356E-15,-25.)); +#1720=CARTESIAN_POINT('',(0.,-23.250635094611,12.5)); +#1721=CARTESIAN_POINT('Origin',(0.,-21.650635094611,12.5)); +#1722=CARTESIAN_POINT('Origin',(-0.1,0.,-33.4732050807569)); +#1723=CARTESIAN_POINT('',(-0.0133974596215561,0.,-33.5232050807569)); +#1724=CARTESIAN_POINT('Origin',(-13.2499999999999,0.,-56.4496732002875)); +#1725=CARTESIAN_POINT('',(-12.9016660498395,0.,-55.8463411006084)); +#1726=CARTESIAN_POINT('Origin',(-7.5,21.650635094611,-251.5)); +#1727=CARTESIAN_POINT('',(0.,20.050635094611,-251.5)); +#1728=CARTESIAN_POINT('',(-7.5,20.050635094611,-251.5)); +#1729=CARTESIAN_POINT('Origin',(0.,21.650635094611,-251.5)); +#1730=CARTESIAN_POINT('Origin',(-7.5,-21.650635094611,-251.5)); +#1731=CARTESIAN_POINT('',(0.,-23.250635094611,-251.5)); +#1732=CARTESIAN_POINT('',(-7.5,-23.250635094611,-251.5)); +#1733=CARTESIAN_POINT('Origin',(0.,-21.650635094611,-251.5)); +#1734=CARTESIAN_POINT('Origin',(-7.5,-21.650635094611,12.5)); +#1735=CARTESIAN_POINT('',(2.5,-23.250635094611,12.5)); +#1736=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,12.5)); +#1737=CARTESIAN_POINT('',(-7.5,-23.250635094611,12.5)); +#1738=CARTESIAN_POINT('Origin',(-7.5,7.36484746826356E-15,-25.)); +#1739=CARTESIAN_POINT('',(2.5,-1.59999999999999,-25.)); +#1740=CARTESIAN_POINT('Origin',(2.5,7.36484746826356E-15,-25.)); +#1741=CARTESIAN_POINT('',(-7.5,-1.59999999999999,-25.)); +#1742=CARTESIAN_POINT('Origin',(-7.5,21.650635094611,12.5)); +#1743=CARTESIAN_POINT('',(2.5,20.050635094611,12.5)); +#1744=CARTESIAN_POINT('Origin',(2.5,21.650635094611,12.5)); +#1745=CARTESIAN_POINT('',(-7.5,20.050635094611,12.5)); +#1746=CARTESIAN_POINT('Origin',(-7.5,21.650635094611,-12.5)); +#1747=CARTESIAN_POINT('',(2.5,20.050635094611,-12.5)); +#1748=CARTESIAN_POINT('Origin',(2.5,21.650635094611,-12.5)); +#1749=CARTESIAN_POINT('',(-7.5,20.050635094611,-12.5)); +#1750=CARTESIAN_POINT('Origin',(-7.5,-21.650635094611,-12.5)); +#1751=CARTESIAN_POINT('',(2.5,-23.250635094611,-12.5)); +#1752=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,-12.5)); +#1753=CARTESIAN_POINT('',(-7.5,-23.250635094611,-12.5)); +#1754=CARTESIAN_POINT('Origin',(-7.5,-21.650635094611,-276.5)); +#1755=CARTESIAN_POINT('',(0.,-23.250635094611,-276.5)); +#1756=CARTESIAN_POINT('',(-7.5,-23.250635094611,-276.5)); +#1757=CARTESIAN_POINT('Origin',(0.,-21.650635094611,-276.5)); +#1758=CARTESIAN_POINT('Origin',(-7.5,7.36484746826356E-15,-239.)); +#1759=CARTESIAN_POINT('',(0.,-1.59999999999999,-239.)); +#1760=CARTESIAN_POINT('',(-7.5,-1.59999999999999,-239.)); +#1761=CARTESIAN_POINT('Origin',(0.,7.36484746826356E-15,-239.)); +#1762=CARTESIAN_POINT('Origin',(-7.5,21.650635094611,-276.5)); +#1763=CARTESIAN_POINT('',(0.,20.050635094611,-276.5)); +#1764=CARTESIAN_POINT('',(-7.5,20.050635094611,-276.5)); +#1765=CARTESIAN_POINT('Origin',(0.,21.650635094611,-276.5)); +#1766=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1767=CARTESIAN_POINT('',(2.5,-21.4999999308655,-0.00121917627727342)); +#1768=CARTESIAN_POINT('',(2.5,-21.4999998617311,-0.00243835255454935)); +#1769=CARTESIAN_POINT('',(2.5,21.4999999308655,-0.00121917627727103)); +#1770=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1771=CARTESIAN_POINT('',(2.5,21.5,6.42939637984833E-16)); +#1772=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1773=CARTESIAN_POINT('',(2.5,18.6195461813654,10.75)); +#1774=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1775=CARTESIAN_POINT('',(2.5,18.6195461813654,10.75)); +#1776=CARTESIAN_POINT('Origin',(2.5,21.650635094611,12.5)); +#1777=CARTESIAN_POINT('',(2.5,24.6817240078565,14.25)); +#1778=CARTESIAN_POINT('Origin',(2.5,21.650635094611,12.5)); +#1779=CARTESIAN_POINT('',(2.5,24.6817240078565,14.25)); +#1780=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1781=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1782=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1783=CARTESIAN_POINT('',(2.5,-28.5000002963676,0.0014077834583465)); +#1784=CARTESIAN_POINT('',(2.5,-28.5000002963676,0.0014077834583465)); +#1785=CARTESIAN_POINT('',(2.5,-24.6817240078565,14.25)); +#1786=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1787=CARTESIAN_POINT('',(2.5,-24.6817240078565,14.25)); +#1788=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,12.5)); +#1789=CARTESIAN_POINT('',(2.5,-18.6195461813654,10.75)); +#1790=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,12.5)); +#1791=CARTESIAN_POINT('',(2.5,-18.6195461813654,10.75)); +#1792=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1793=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1794=CARTESIAN_POINT('Origin',(2.5,0.,-264.)); +#1795=CARTESIAN_POINT('',(0.,24.6817240078565,-278.25)); +#1796=CARTESIAN_POINT('Origin',(0.,0.,-264.)); +#1797=CARTESIAN_POINT('',(2.5,24.6817240078565,-278.25)); +#1798=CARTESIAN_POINT('Origin',(2.5,21.650635094611,-276.5)); +#1799=CARTESIAN_POINT('',(0.,18.6195461813654,-274.75)); +#1800=CARTESIAN_POINT('Origin',(0.,21.650635094611,-276.5)); +#1801=CARTESIAN_POINT('',(2.5,18.6195461813654,-274.75)); +#1802=CARTESIAN_POINT('Origin',(2.5,0.,-264.)); +#1803=CARTESIAN_POINT('',(0.,-18.6195461813654,-274.75)); +#1804=CARTESIAN_POINT('Origin',(0.,0.,-264.)); +#1805=CARTESIAN_POINT('',(2.5,-18.6195461813654,-274.75)); +#1806=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,-276.5)); +#1807=CARTESIAN_POINT('',(0.,-24.6817240078565,-278.25)); +#1808=CARTESIAN_POINT('Origin',(0.,-21.650635094611,-276.5)); +#1809=CARTESIAN_POINT('',(2.5,-24.6817240078565,-278.25)); +#1810=CARTESIAN_POINT('Origin',(2.5,0.,-264.)); +#1811=CARTESIAN_POINT('Origin',(0.,0.,-264.)); +#1812=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1813=CARTESIAN_POINT('',(2.5,0.,-33.4732050807569)); +#1814=CARTESIAN_POINT('',(2.5,-28.5,0.)); +#1815=CARTESIAN_POINT('Origin',(0.,-28.5,-6.73660254037844)); +#1816=CARTESIAN_POINT('Origin',(-11.0849364905388,0.,-57.6996732002875)); +#1817=CARTESIAN_POINT('',(2.15166604983954,0.,-34.7732050807569)); +#1818=CARTESIAN_POINT('Origin',(-0.1,0.,-33.4732050807569)); +#1819=CARTESIAN_POINT('Origin',(-10.65,0.,-206.853658899391)); +#1820=CARTESIAN_POINT('',(-13.25,0.,-206.853658899391)); +#1821=CARTESIAN_POINT('',(-12.9016660498395,0.,-208.153658899391)); +#1822=CARTESIAN_POINT('Origin',(-13.25,0.,-207.550326799712)); +#1823=CARTESIAN_POINT('',(-13.2499999999999,0.,-57.1463411006084)); +#1824=CARTESIAN_POINT('Origin',(1.84889274661175E-31,0.,-230.5)); +#1825=CARTESIAN_POINT('',(-0.0133974596215698,0.,-230.476794919243)); +#1826=CARTESIAN_POINT('Origin',(-10.6499999999999,0.,-57.1463411006084)); +#1827=CARTESIAN_POINT('Origin',(-0.1,0.,-230.526794919243)); +#1828=CARTESIAN_POINT('',(0.,0.,-230.526794919243)); +#1829=CARTESIAN_POINT('Origin',(0.,0.,-284.)); +#1830=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1834, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1831=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1834, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1832=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1830)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1834,#1836,#1837)) +REPRESENTATION_CONTEXT('','3D') +); +#1833=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1831)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1834,#1836,#1837)) +REPRESENTATION_CONTEXT('','3D') +); +#1834=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#1835=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT($,.METRE.) +); +#1836=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#1837=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#1838=SHAPE_DEFINITION_REPRESENTATION(#1839,#1840); +#1839=PRODUCT_DEFINITION_SHAPE('',$,#1842); +#1840=SHAPE_REPRESENTATION('',(#1070),#1832); +#1841=PRODUCT_DEFINITION_CONTEXT('part definition',#1846,'design'); +#1842=PRODUCT_DEFINITION('link2-3','link2-3 v2',#1843,#1841); +#1843=PRODUCT_DEFINITION_FORMATION('',$,#1848); +#1844=PRODUCT_RELATED_PRODUCT_CATEGORY('link2-3 v2','link2-3 v2',(#1848)); +#1845=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#1846); +#1846=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#1847=PRODUCT_CONTEXT('part definition',#1846,'mechanical'); +#1848=PRODUCT('link2-3','link2-3 v2',$,(#1847)); +#1849=PRESENTATION_STYLE_ASSIGNMENT((#1851)); +#1850=PRESENTATION_STYLE_ASSIGNMENT((#1852)); +#1851=SURFACE_STYLE_USAGE(.BOTH.,#1853); +#1852=SURFACE_STYLE_USAGE(.BOTH.,#1854); +#1853=SURFACE_SIDE_STYLE('',(#1855)); +#1854=SURFACE_SIDE_STYLE('',(#1856)); +#1855=SURFACE_STYLE_FILL_AREA(#1857); +#1856=SURFACE_STYLE_FILL_AREA(#1858); +#1857=FILL_AREA_STYLE('Steel - Satin',(#1859)); +#1858=FILL_AREA_STYLE('Aluminum - Satin',(#1860)); +#1859=FILL_AREA_STYLE_COLOUR('Steel - Satin',#1861); +#1860=FILL_AREA_STYLE_COLOUR('Aluminum - Satin',#1862); +#1861=COLOUR_RGB('Steel - Satin',0.627450980392157,0.627450980392157,0.627450980392157); +#1862=COLOUR_RGB('Aluminum - Satin',0.96078431372549,0.96078431372549,0.964705882352941); +ENDSEC; +END-ISO-10303-21; diff --git a/hardware/follower_STEPs/link3-4-1-adjusted_v0.2.0.step b/hardware/follower_STEPs/link3-4-1-adjusted_v0.2.0.step new file mode 100644 index 0000000000000000000000000000000000000000..0339451efd97d9d37fdc31516f1c3ed0980b0164 --- /dev/null +++ b/hardware/follower_STEPs/link3-4-1-adjusted_v0.2.0.step @@ -0,0 +1,1135 @@ +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 */ 'link3-4-1 (angestellt).step', +/* time_stamp */ '2025-11-24T15:35:39+01:00', +/* author */ (''), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v20.1', +/* originating_system */ 'Autodesk Translation Framework v14.21.0.0', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#1047); +#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#1054,#12); +#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#1046); +#13=STYLED_ITEM('',(#1064),#14); +#14=MANIFOLD_SOLID_BREP('Body1',#611); +#15=FACE_BOUND('',#104,.T.); +#16=FACE_BOUND('',#105,.T.); +#17=FACE_BOUND('',#106,.T.); +#18=FACE_BOUND('',#107,.T.); +#19=FACE_BOUND('',#108,.T.); +#20=FACE_BOUND('',#109,.T.); +#21=FACE_BOUND('',#110,.T.); +#22=FACE_BOUND('',#113,.T.); +#23=FACE_BOUND('',#114,.T.); +#24=FACE_BOUND('',#115,.T.); +#25=FACE_BOUND('',#116,.T.); +#26=FACE_BOUND('',#117,.T.); +#27=FACE_BOUND('',#118,.T.); +#28=FACE_BOUND('',#119,.T.); +#29=FACE_BOUND('',#121,.T.); +#30=FACE_BOUND('',#122,.T.); +#31=FACE_BOUND('',#123,.T.); +#32=FACE_BOUND('',#124,.T.); +#33=FACE_BOUND('',#125,.T.); +#34=FACE_BOUND('',#130,.T.); +#35=FACE_BOUND('',#131,.T.); +#36=FACE_BOUND('',#132,.T.); +#37=FACE_BOUND('',#133,.T.); +#38=FACE_BOUND('',#134,.T.); +#39=PLANE('',#664); +#40=PLANE('',#665); +#41=PLANE('',#666); +#42=PLANE('',#667); +#43=PLANE('',#668); +#44=PLANE('',#675); +#45=PLANE('',#676); +#46=PLANE('',#683); +#47=PLANE('',#687); +#48=PLANE('',#688); +#49=PLANE('',#689); +#50=PLANE('',#690); +#51=PLANE('',#691); +#52=PLANE('',#692); +#53=PLANE('',#693); +#54=PLANE('',#694); +#55=FACE_OUTER_BOUND('',#89,.T.); +#56=FACE_OUTER_BOUND('',#90,.T.); +#57=FACE_OUTER_BOUND('',#91,.T.); +#58=FACE_OUTER_BOUND('',#92,.T.); +#59=FACE_OUTER_BOUND('',#93,.T.); +#60=FACE_OUTER_BOUND('',#94,.T.); +#61=FACE_OUTER_BOUND('',#95,.T.); +#62=FACE_OUTER_BOUND('',#96,.T.); +#63=FACE_OUTER_BOUND('',#97,.T.); +#64=FACE_OUTER_BOUND('',#98,.T.); +#65=FACE_OUTER_BOUND('',#99,.T.); +#66=FACE_OUTER_BOUND('',#100,.T.); +#67=FACE_OUTER_BOUND('',#101,.T.); +#68=FACE_OUTER_BOUND('',#102,.T.); +#69=FACE_OUTER_BOUND('',#103,.T.); +#70=FACE_OUTER_BOUND('',#111,.T.); +#71=FACE_OUTER_BOUND('',#112,.T.); +#72=FACE_OUTER_BOUND('',#120,.T.); +#73=FACE_OUTER_BOUND('',#126,.T.); +#74=FACE_OUTER_BOUND('',#127,.T.); +#75=FACE_OUTER_BOUND('',#128,.T.); +#76=FACE_OUTER_BOUND('',#129,.T.); +#77=FACE_OUTER_BOUND('',#135,.T.); +#78=FACE_OUTER_BOUND('',#136,.T.); +#79=FACE_OUTER_BOUND('',#137,.T.); +#80=FACE_OUTER_BOUND('',#138,.T.); +#81=FACE_OUTER_BOUND('',#139,.T.); +#82=FACE_OUTER_BOUND('',#140,.T.); +#83=FACE_OUTER_BOUND('',#141,.T.); +#84=FACE_OUTER_BOUND('',#142,.T.); +#85=FACE_OUTER_BOUND('',#143,.T.); +#86=FACE_OUTER_BOUND('',#144,.T.); +#87=FACE_OUTER_BOUND('',#145,.T.); +#88=FACE_OUTER_BOUND('',#146,.T.); +#89=EDGE_LOOP('',(#399,#400,#401,#402)); +#90=EDGE_LOOP('',(#403,#404,#405,#406)); +#91=EDGE_LOOP('',(#407,#408,#409,#410)); +#92=EDGE_LOOP('',(#411,#412,#413,#414)); +#93=EDGE_LOOP('',(#415,#416,#417,#418)); +#94=EDGE_LOOP('',(#419,#420,#421,#422)); +#95=EDGE_LOOP('',(#423,#424,#425,#426)); +#96=EDGE_LOOP('',(#427,#428,#429,#430)); +#97=EDGE_LOOP('',(#431,#432,#433,#434)); +#98=EDGE_LOOP('',(#435,#436,#437,#438)); +#99=EDGE_LOOP('',(#439,#440,#441,#442)); +#100=EDGE_LOOP('',(#443,#444,#445,#446)); +#101=EDGE_LOOP('',(#447,#448,#449,#450)); +#102=EDGE_LOOP('',(#451,#452,#453,#454)); +#103=EDGE_LOOP('',(#455,#456,#457,#458)); +#104=EDGE_LOOP('',(#459)); +#105=EDGE_LOOP('',(#460)); +#106=EDGE_LOOP('',(#461)); +#107=EDGE_LOOP('',(#462)); +#108=EDGE_LOOP('',(#463)); +#109=EDGE_LOOP('',(#464)); +#110=EDGE_LOOP('',(#465)); +#111=EDGE_LOOP('',(#466,#467,#468,#469)); +#112=EDGE_LOOP('',(#470,#471,#472,#473)); +#113=EDGE_LOOP('',(#474)); +#114=EDGE_LOOP('',(#475)); +#115=EDGE_LOOP('',(#476)); +#116=EDGE_LOOP('',(#477)); +#117=EDGE_LOOP('',(#478)); +#118=EDGE_LOOP('',(#479)); +#119=EDGE_LOOP('',(#480)); +#120=EDGE_LOOP('',(#481,#482,#483,#484)); +#121=EDGE_LOOP('',(#485)); +#122=EDGE_LOOP('',(#486)); +#123=EDGE_LOOP('',(#487)); +#124=EDGE_LOOP('',(#488)); +#125=EDGE_LOOP('',(#489)); +#126=EDGE_LOOP('',(#490,#491,#492,#493)); +#127=EDGE_LOOP('',(#494,#495,#496,#497)); +#128=EDGE_LOOP('',(#498,#499,#500,#501)); +#129=EDGE_LOOP('',(#502,#503,#504,#505)); +#130=EDGE_LOOP('',(#506)); +#131=EDGE_LOOP('',(#507)); +#132=EDGE_LOOP('',(#508)); +#133=EDGE_LOOP('',(#509)); +#134=EDGE_LOOP('',(#510)); +#135=EDGE_LOOP('',(#511,#512,#513,#514)); +#136=EDGE_LOOP('',(#515,#516,#517,#518)); +#137=EDGE_LOOP('',(#519,#520,#521,#522)); +#138=EDGE_LOOP('',(#523,#524,#525,#526)); +#139=EDGE_LOOP('',(#527,#528,#529,#530)); +#140=EDGE_LOOP('',(#531,#532,#533,#534)); +#141=EDGE_LOOP('',(#535,#536,#537,#538)); +#142=EDGE_LOOP('',(#539,#540,#541,#542)); +#143=EDGE_LOOP('',(#543,#544,#545,#546)); +#144=EDGE_LOOP('',(#547,#548,#549,#550)); +#145=EDGE_LOOP('',(#551,#552,#553,#554)); +#146=EDGE_LOOP('',(#555,#556,#557,#558)); +#147=LINE('',#886,#191); +#148=LINE('',#892,#192); +#149=LINE('',#898,#193); +#150=LINE('',#904,#194); +#151=LINE('',#910,#195); +#152=LINE('',#916,#196); +#153=LINE('',#922,#197); +#154=LINE('',#928,#198); +#155=LINE('',#934,#199); +#156=LINE('',#940,#200); +#157=LINE('',#946,#201); +#158=LINE('',#953,#202); +#159=LINE('',#956,#203); +#160=LINE('',#961,#204); +#161=LINE('',#965,#205); +#162=LINE('',#967,#206); +#163=LINE('',#968,#207); +#164=LINE('',#971,#208); +#165=LINE('',#972,#209); +#166=LINE('',#975,#210); +#167=LINE('',#976,#211); +#168=LINE('',#978,#212); +#169=LINE('',#984,#213); +#170=LINE('',#986,#214); +#171=LINE('',#987,#215); +#172=LINE('',#992,#216); +#173=LINE('',#993,#217); +#174=LINE('',#999,#218); +#175=LINE('',#1002,#219); +#176=LINE('',#1005,#220); +#177=LINE('',#1007,#221); +#178=LINE('',#1008,#222); +#179=LINE('',#1010,#223); +#180=LINE('',#1011,#224); +#181=LINE('',#1019,#225); +#182=LINE('',#1023,#226); +#183=LINE('',#1025,#227); +#184=LINE('',#1026,#228); +#185=LINE('',#1031,#229); +#186=LINE('',#1032,#230); +#187=LINE('',#1034,#231); +#188=LINE('',#1035,#232); +#189=LINE('',#1037,#233); +#190=LINE('',#1039,#234); +#191=VECTOR('',#701,7.); +#192=VECTOR('',#708,1.6); +#193=VECTOR('',#715,1.6); +#194=VECTOR('',#722,1.6); +#195=VECTOR('',#729,1.6); +#196=VECTOR('',#736,1.6); +#197=VECTOR('',#743,1.6); +#198=VECTOR('',#750,1.6); +#199=VECTOR('',#757,1.6); +#200=VECTOR('',#764,1.6); +#201=VECTOR('',#771,1.6); +#202=VECTOR('',#778,10.); +#203=VECTOR('',#781,10.); +#204=VECTOR('',#786,7.00000000000001); +#205=VECTOR('',#791,10.); +#206=VECTOR('',#792,10.); +#207=VECTOR('',#793,10.); +#208=VECTOR('',#796,10.); +#209=VECTOR('',#797,10.); +#210=VECTOR('',#800,10.); +#211=VECTOR('',#801,10.); +#212=VECTOR('',#804,10.); +#213=VECTOR('',#809,10.); +#214=VECTOR('',#810,10.); +#215=VECTOR('',#811,10.); +#216=VECTOR('',#816,10.); +#217=VECTOR('',#817,10.); +#218=VECTOR('',#822,10.); +#219=VECTOR('',#825,10.); +#220=VECTOR('',#828,10.); +#221=VECTOR('',#829,10.); +#222=VECTOR('',#830,10.); +#223=VECTOR('',#833,10.); +#224=VECTOR('',#834,10.); +#225=VECTOR('',#845,10.); +#226=VECTOR('',#850,10.); +#227=VECTOR('',#851,10.); +#228=VECTOR('',#852,10.); +#229=VECTOR('',#861,10.); +#230=VECTOR('',#862,10.); +#231=VECTOR('',#865,10.); +#232=VECTOR('',#866,10.); +#233=VECTOR('',#869,10.); +#234=VECTOR('',#872,10.); +#235=CIRCLE('',#626,7.); +#236=CIRCLE('',#627,7.); +#237=CIRCLE('',#629,1.6); +#238=CIRCLE('',#630,1.6); +#239=CIRCLE('',#632,1.6); +#240=CIRCLE('',#633,1.6); +#241=CIRCLE('',#635,1.6); +#242=CIRCLE('',#636,1.6); +#243=CIRCLE('',#638,1.6); +#244=CIRCLE('',#639,1.6); +#245=CIRCLE('',#641,1.6); +#246=CIRCLE('',#642,1.6); +#247=CIRCLE('',#644,1.6); +#248=CIRCLE('',#645,1.6); +#249=CIRCLE('',#647,1.6); +#250=CIRCLE('',#648,1.6); +#251=CIRCLE('',#650,1.6); +#252=CIRCLE('',#651,1.6); +#253=CIRCLE('',#653,1.6); +#254=CIRCLE('',#654,1.6); +#255=CIRCLE('',#656,1.6); +#256=CIRCLE('',#657,1.6); +#257=CIRCLE('',#659,17.5); +#258=CIRCLE('',#660,17.5); +#259=CIRCLE('',#662,7.00000000000001); +#260=CIRCLE('',#663,7.00000000000001); +#261=CIRCLE('',#669,17.5); +#262=CIRCLE('',#671,17.5); +#263=CIRCLE('',#673,0.0999999999999996); +#264=CIRCLE('',#674,0.0999999999999996); +#265=CIRCLE('',#678,2.6); +#266=CIRCLE('',#679,2.6); +#267=CIRCLE('',#681,2.6); +#268=CIRCLE('',#682,2.6); +#269=CIRCLE('',#685,0.0999999999999991); +#270=CIRCLE('',#686,0.0999999999999991); +#271=VERTEX_POINT('',#883); +#272=VERTEX_POINT('',#885); +#273=VERTEX_POINT('',#889); +#274=VERTEX_POINT('',#891); +#275=VERTEX_POINT('',#895); +#276=VERTEX_POINT('',#897); +#277=VERTEX_POINT('',#901); +#278=VERTEX_POINT('',#903); +#279=VERTEX_POINT('',#907); +#280=VERTEX_POINT('',#909); +#281=VERTEX_POINT('',#913); +#282=VERTEX_POINT('',#915); +#283=VERTEX_POINT('',#919); +#284=VERTEX_POINT('',#921); +#285=VERTEX_POINT('',#925); +#286=VERTEX_POINT('',#927); +#287=VERTEX_POINT('',#931); +#288=VERTEX_POINT('',#933); +#289=VERTEX_POINT('',#937); +#290=VERTEX_POINT('',#939); +#291=VERTEX_POINT('',#943); +#292=VERTEX_POINT('',#945); +#293=VERTEX_POINT('',#949); +#294=VERTEX_POINT('',#950); +#295=VERTEX_POINT('',#952); +#296=VERTEX_POINT('',#954); +#297=VERTEX_POINT('',#958); +#298=VERTEX_POINT('',#960); +#299=VERTEX_POINT('',#964); +#300=VERTEX_POINT('',#966); +#301=VERTEX_POINT('',#970); +#302=VERTEX_POINT('',#974); +#303=VERTEX_POINT('',#980); +#304=VERTEX_POINT('',#981); +#305=VERTEX_POINT('',#983); +#306=VERTEX_POINT('',#985); +#307=VERTEX_POINT('',#989); +#308=VERTEX_POINT('',#990); +#309=VERTEX_POINT('',#995); +#310=VERTEX_POINT('',#996); +#311=VERTEX_POINT('',#998); +#312=VERTEX_POINT('',#1000); +#313=VERTEX_POINT('',#1004); +#314=VERTEX_POINT('',#1006); +#315=VERTEX_POINT('',#1016); +#316=VERTEX_POINT('',#1018); +#317=VERTEX_POINT('',#1022); +#318=VERTEX_POINT('',#1024); +#319=EDGE_CURVE('',#271,#271,#235,.T.); +#320=EDGE_CURVE('',#271,#272,#147,.T.); +#321=EDGE_CURVE('',#272,#272,#236,.T.); +#322=EDGE_CURVE('',#273,#273,#237,.T.); +#323=EDGE_CURVE('',#273,#274,#148,.T.); +#324=EDGE_CURVE('',#274,#274,#238,.T.); +#325=EDGE_CURVE('',#275,#275,#239,.T.); +#326=EDGE_CURVE('',#275,#276,#149,.T.); +#327=EDGE_CURVE('',#276,#276,#240,.T.); +#328=EDGE_CURVE('',#277,#277,#241,.T.); +#329=EDGE_CURVE('',#277,#278,#150,.T.); +#330=EDGE_CURVE('',#278,#278,#242,.T.); +#331=EDGE_CURVE('',#279,#279,#243,.T.); +#332=EDGE_CURVE('',#279,#280,#151,.T.); +#333=EDGE_CURVE('',#280,#280,#244,.T.); +#334=EDGE_CURVE('',#281,#281,#245,.T.); +#335=EDGE_CURVE('',#281,#282,#152,.T.); +#336=EDGE_CURVE('',#282,#282,#246,.T.); +#337=EDGE_CURVE('',#283,#283,#247,.T.); +#338=EDGE_CURVE('',#283,#284,#153,.T.); +#339=EDGE_CURVE('',#284,#284,#248,.T.); +#340=EDGE_CURVE('',#285,#285,#249,.T.); +#341=EDGE_CURVE('',#285,#286,#154,.T.); +#342=EDGE_CURVE('',#286,#286,#250,.T.); +#343=EDGE_CURVE('',#287,#287,#251,.T.); +#344=EDGE_CURVE('',#287,#288,#155,.T.); +#345=EDGE_CURVE('',#288,#288,#252,.T.); +#346=EDGE_CURVE('',#289,#289,#253,.T.); +#347=EDGE_CURVE('',#289,#290,#156,.T.); +#348=EDGE_CURVE('',#290,#290,#254,.T.); +#349=EDGE_CURVE('',#291,#291,#255,.T.); +#350=EDGE_CURVE('',#291,#292,#157,.T.); +#351=EDGE_CURVE('',#292,#292,#256,.T.); +#352=EDGE_CURVE('',#293,#294,#257,.T.); +#353=EDGE_CURVE('',#293,#295,#158,.T.); +#354=EDGE_CURVE('',#296,#295,#258,.T.); +#355=EDGE_CURVE('',#294,#296,#159,.T.); +#356=EDGE_CURVE('',#297,#297,#259,.T.); +#357=EDGE_CURVE('',#297,#298,#160,.T.); +#358=EDGE_CURVE('',#298,#298,#260,.T.); +#359=EDGE_CURVE('',#299,#293,#161,.T.); +#360=EDGE_CURVE('',#299,#300,#162,.T.); +#361=EDGE_CURVE('',#300,#295,#163,.T.); +#362=EDGE_CURVE('',#301,#294,#164,.T.); +#363=EDGE_CURVE('',#301,#299,#165,.T.); +#364=EDGE_CURVE('',#302,#296,#166,.T.); +#365=EDGE_CURVE('',#301,#302,#167,.T.); +#366=EDGE_CURVE('',#302,#300,#168,.T.); +#367=EDGE_CURVE('',#303,#304,#261,.T.); +#368=EDGE_CURVE('',#303,#305,#169,.T.); +#369=EDGE_CURVE('',#305,#306,#170,.T.); +#370=EDGE_CURVE('',#304,#306,#171,.T.); +#371=EDGE_CURVE('',#307,#308,#262,.T.); +#372=EDGE_CURVE('',#308,#303,#172,.T.); +#373=EDGE_CURVE('',#304,#307,#173,.T.); +#374=EDGE_CURVE('',#309,#310,#263,.T.); +#375=EDGE_CURVE('',#310,#311,#174,.T.); +#376=EDGE_CURVE('',#311,#312,#264,.T.); +#377=EDGE_CURVE('',#312,#309,#175,.T.); +#378=EDGE_CURVE('',#312,#313,#176,.T.); +#379=EDGE_CURVE('',#314,#313,#177,.T.); +#380=EDGE_CURVE('',#309,#314,#178,.T.); +#381=EDGE_CURVE('',#307,#311,#179,.T.); +#382=EDGE_CURVE('',#308,#310,#180,.T.); +#383=EDGE_CURVE('',#300,#314,#265,.T.); +#384=EDGE_CURVE('',#313,#302,#266,.T.); +#385=EDGE_CURVE('',#315,#305,#267,.T.); +#386=EDGE_CURVE('',#316,#315,#181,.T.); +#387=EDGE_CURVE('',#306,#316,#268,.T.); +#388=EDGE_CURVE('',#315,#317,#182,.T.); +#389=EDGE_CURVE('',#317,#318,#183,.T.); +#390=EDGE_CURVE('',#316,#318,#184,.T.); +#391=EDGE_CURVE('',#299,#317,#269,.T.); +#392=EDGE_CURVE('',#318,#301,#270,.T.); +#393=EDGE_CURVE('',#305,#310,#185,.T.); +#394=EDGE_CURVE('',#315,#309,#186,.T.); +#395=EDGE_CURVE('',#316,#312,#187,.T.); +#396=EDGE_CURVE('',#306,#311,#188,.T.); +#397=EDGE_CURVE('',#318,#313,#189,.T.); +#398=EDGE_CURVE('',#317,#314,#190,.T.); +#399=ORIENTED_EDGE('',*,*,#319,.F.); +#400=ORIENTED_EDGE('',*,*,#320,.T.); +#401=ORIENTED_EDGE('',*,*,#321,.F.); +#402=ORIENTED_EDGE('',*,*,#320,.F.); +#403=ORIENTED_EDGE('',*,*,#322,.F.); +#404=ORIENTED_EDGE('',*,*,#323,.T.); +#405=ORIENTED_EDGE('',*,*,#324,.F.); +#406=ORIENTED_EDGE('',*,*,#323,.F.); +#407=ORIENTED_EDGE('',*,*,#325,.F.); +#408=ORIENTED_EDGE('',*,*,#326,.T.); +#409=ORIENTED_EDGE('',*,*,#327,.F.); +#410=ORIENTED_EDGE('',*,*,#326,.F.); +#411=ORIENTED_EDGE('',*,*,#328,.F.); +#412=ORIENTED_EDGE('',*,*,#329,.T.); +#413=ORIENTED_EDGE('',*,*,#330,.F.); +#414=ORIENTED_EDGE('',*,*,#329,.F.); +#415=ORIENTED_EDGE('',*,*,#331,.F.); +#416=ORIENTED_EDGE('',*,*,#332,.T.); +#417=ORIENTED_EDGE('',*,*,#333,.F.); +#418=ORIENTED_EDGE('',*,*,#332,.F.); +#419=ORIENTED_EDGE('',*,*,#334,.F.); +#420=ORIENTED_EDGE('',*,*,#335,.T.); +#421=ORIENTED_EDGE('',*,*,#336,.F.); +#422=ORIENTED_EDGE('',*,*,#335,.F.); +#423=ORIENTED_EDGE('',*,*,#337,.F.); +#424=ORIENTED_EDGE('',*,*,#338,.T.); +#425=ORIENTED_EDGE('',*,*,#339,.F.); +#426=ORIENTED_EDGE('',*,*,#338,.F.); +#427=ORIENTED_EDGE('',*,*,#340,.F.); +#428=ORIENTED_EDGE('',*,*,#341,.T.); +#429=ORIENTED_EDGE('',*,*,#342,.F.); +#430=ORIENTED_EDGE('',*,*,#341,.F.); +#431=ORIENTED_EDGE('',*,*,#343,.F.); +#432=ORIENTED_EDGE('',*,*,#344,.T.); +#433=ORIENTED_EDGE('',*,*,#345,.F.); +#434=ORIENTED_EDGE('',*,*,#344,.F.); +#435=ORIENTED_EDGE('',*,*,#346,.F.); +#436=ORIENTED_EDGE('',*,*,#347,.T.); +#437=ORIENTED_EDGE('',*,*,#348,.F.); +#438=ORIENTED_EDGE('',*,*,#347,.F.); +#439=ORIENTED_EDGE('',*,*,#349,.F.); +#440=ORIENTED_EDGE('',*,*,#350,.T.); +#441=ORIENTED_EDGE('',*,*,#351,.F.); +#442=ORIENTED_EDGE('',*,*,#350,.F.); +#443=ORIENTED_EDGE('',*,*,#352,.F.); +#444=ORIENTED_EDGE('',*,*,#353,.T.); +#445=ORIENTED_EDGE('',*,*,#354,.F.); +#446=ORIENTED_EDGE('',*,*,#355,.F.); +#447=ORIENTED_EDGE('',*,*,#356,.F.); +#448=ORIENTED_EDGE('',*,*,#357,.T.); +#449=ORIENTED_EDGE('',*,*,#358,.F.); +#450=ORIENTED_EDGE('',*,*,#357,.F.); +#451=ORIENTED_EDGE('',*,*,#353,.F.); +#452=ORIENTED_EDGE('',*,*,#359,.F.); +#453=ORIENTED_EDGE('',*,*,#360,.T.); +#454=ORIENTED_EDGE('',*,*,#361,.T.); +#455=ORIENTED_EDGE('',*,*,#352,.T.); +#456=ORIENTED_EDGE('',*,*,#362,.F.); +#457=ORIENTED_EDGE('',*,*,#363,.T.); +#458=ORIENTED_EDGE('',*,*,#359,.T.); +#459=ORIENTED_EDGE('',*,*,#358,.T.); +#460=ORIENTED_EDGE('',*,*,#351,.T.); +#461=ORIENTED_EDGE('',*,*,#348,.T.); +#462=ORIENTED_EDGE('',*,*,#345,.T.); +#463=ORIENTED_EDGE('',*,*,#342,.T.); +#464=ORIENTED_EDGE('',*,*,#339,.T.); +#465=ORIENTED_EDGE('',*,*,#336,.T.); +#466=ORIENTED_EDGE('',*,*,#355,.T.); +#467=ORIENTED_EDGE('',*,*,#364,.F.); +#468=ORIENTED_EDGE('',*,*,#365,.F.); +#469=ORIENTED_EDGE('',*,*,#362,.T.); +#470=ORIENTED_EDGE('',*,*,#354,.T.); +#471=ORIENTED_EDGE('',*,*,#361,.F.); +#472=ORIENTED_EDGE('',*,*,#366,.F.); +#473=ORIENTED_EDGE('',*,*,#364,.T.); +#474=ORIENTED_EDGE('',*,*,#334,.T.); +#475=ORIENTED_EDGE('',*,*,#337,.T.); +#476=ORIENTED_EDGE('',*,*,#340,.T.); +#477=ORIENTED_EDGE('',*,*,#343,.T.); +#478=ORIENTED_EDGE('',*,*,#346,.T.); +#479=ORIENTED_EDGE('',*,*,#349,.T.); +#480=ORIENTED_EDGE('',*,*,#356,.T.); +#481=ORIENTED_EDGE('',*,*,#367,.F.); +#482=ORIENTED_EDGE('',*,*,#368,.T.); +#483=ORIENTED_EDGE('',*,*,#369,.T.); +#484=ORIENTED_EDGE('',*,*,#370,.F.); +#485=ORIENTED_EDGE('',*,*,#321,.T.); +#486=ORIENTED_EDGE('',*,*,#324,.T.); +#487=ORIENTED_EDGE('',*,*,#327,.T.); +#488=ORIENTED_EDGE('',*,*,#330,.T.); +#489=ORIENTED_EDGE('',*,*,#333,.T.); +#490=ORIENTED_EDGE('',*,*,#371,.T.); +#491=ORIENTED_EDGE('',*,*,#372,.T.); +#492=ORIENTED_EDGE('',*,*,#367,.T.); +#493=ORIENTED_EDGE('',*,*,#373,.T.); +#494=ORIENTED_EDGE('',*,*,#374,.T.); +#495=ORIENTED_EDGE('',*,*,#375,.T.); +#496=ORIENTED_EDGE('',*,*,#376,.T.); +#497=ORIENTED_EDGE('',*,*,#377,.T.); +#498=ORIENTED_EDGE('',*,*,#377,.F.); +#499=ORIENTED_EDGE('',*,*,#378,.T.); +#500=ORIENTED_EDGE('',*,*,#379,.F.); +#501=ORIENTED_EDGE('',*,*,#380,.F.); +#502=ORIENTED_EDGE('',*,*,#371,.F.); +#503=ORIENTED_EDGE('',*,*,#381,.T.); +#504=ORIENTED_EDGE('',*,*,#375,.F.); +#505=ORIENTED_EDGE('',*,*,#382,.F.); +#506=ORIENTED_EDGE('',*,*,#319,.T.); +#507=ORIENTED_EDGE('',*,*,#322,.T.); +#508=ORIENTED_EDGE('',*,*,#325,.T.); +#509=ORIENTED_EDGE('',*,*,#328,.T.); +#510=ORIENTED_EDGE('',*,*,#331,.T.); +#511=ORIENTED_EDGE('',*,*,#383,.T.); +#512=ORIENTED_EDGE('',*,*,#379,.T.); +#513=ORIENTED_EDGE('',*,*,#384,.T.); +#514=ORIENTED_EDGE('',*,*,#366,.T.); +#515=ORIENTED_EDGE('',*,*,#385,.F.); +#516=ORIENTED_EDGE('',*,*,#386,.F.); +#517=ORIENTED_EDGE('',*,*,#387,.F.); +#518=ORIENTED_EDGE('',*,*,#369,.F.); +#519=ORIENTED_EDGE('',*,*,#386,.T.); +#520=ORIENTED_EDGE('',*,*,#388,.T.); +#521=ORIENTED_EDGE('',*,*,#389,.T.); +#522=ORIENTED_EDGE('',*,*,#390,.F.); +#523=ORIENTED_EDGE('',*,*,#391,.F.); +#524=ORIENTED_EDGE('',*,*,#363,.F.); +#525=ORIENTED_EDGE('',*,*,#392,.F.); +#526=ORIENTED_EDGE('',*,*,#389,.F.); +#527=ORIENTED_EDGE('',*,*,#385,.T.); +#528=ORIENTED_EDGE('',*,*,#393,.T.); +#529=ORIENTED_EDGE('',*,*,#374,.F.); +#530=ORIENTED_EDGE('',*,*,#394,.F.); +#531=ORIENTED_EDGE('',*,*,#387,.T.); +#532=ORIENTED_EDGE('',*,*,#395,.T.); +#533=ORIENTED_EDGE('',*,*,#376,.F.); +#534=ORIENTED_EDGE('',*,*,#396,.F.); +#535=ORIENTED_EDGE('',*,*,#390,.T.); +#536=ORIENTED_EDGE('',*,*,#397,.T.); +#537=ORIENTED_EDGE('',*,*,#378,.F.); +#538=ORIENTED_EDGE('',*,*,#395,.F.); +#539=ORIENTED_EDGE('',*,*,#388,.F.); +#540=ORIENTED_EDGE('',*,*,#394,.T.); +#541=ORIENTED_EDGE('',*,*,#380,.T.); +#542=ORIENTED_EDGE('',*,*,#398,.F.); +#543=ORIENTED_EDGE('',*,*,#372,.F.); +#544=ORIENTED_EDGE('',*,*,#382,.T.); +#545=ORIENTED_EDGE('',*,*,#393,.F.); +#546=ORIENTED_EDGE('',*,*,#368,.F.); +#547=ORIENTED_EDGE('',*,*,#373,.F.); +#548=ORIENTED_EDGE('',*,*,#370,.T.); +#549=ORIENTED_EDGE('',*,*,#396,.T.); +#550=ORIENTED_EDGE('',*,*,#381,.F.); +#551=ORIENTED_EDGE('',*,*,#391,.T.); +#552=ORIENTED_EDGE('',*,*,#398,.T.); +#553=ORIENTED_EDGE('',*,*,#383,.F.); +#554=ORIENTED_EDGE('',*,*,#360,.F.); +#555=ORIENTED_EDGE('',*,*,#392,.T.); +#556=ORIENTED_EDGE('',*,*,#365,.T.); +#557=ORIENTED_EDGE('',*,*,#384,.F.); +#558=ORIENTED_EDGE('',*,*,#397,.F.); +#559=CYLINDRICAL_SURFACE('',#625,7.); +#560=CYLINDRICAL_SURFACE('',#628,1.6); +#561=CYLINDRICAL_SURFACE('',#631,1.6); +#562=CYLINDRICAL_SURFACE('',#634,1.6); +#563=CYLINDRICAL_SURFACE('',#637,1.6); +#564=CYLINDRICAL_SURFACE('',#640,1.6); +#565=CYLINDRICAL_SURFACE('',#643,1.6); +#566=CYLINDRICAL_SURFACE('',#646,1.6); +#567=CYLINDRICAL_SURFACE('',#649,1.6); +#568=CYLINDRICAL_SURFACE('',#652,1.6); +#569=CYLINDRICAL_SURFACE('',#655,1.6); +#570=CYLINDRICAL_SURFACE('',#658,17.5); +#571=CYLINDRICAL_SURFACE('',#661,7.00000000000001); +#572=CYLINDRICAL_SURFACE('',#670,17.5); +#573=CYLINDRICAL_SURFACE('',#672,0.1); +#574=CYLINDRICAL_SURFACE('',#677,2.6); +#575=CYLINDRICAL_SURFACE('',#680,2.6); +#576=CYLINDRICAL_SURFACE('',#684,0.1); +#577=ADVANCED_FACE('',(#55),#559,.F.); +#578=ADVANCED_FACE('',(#56),#560,.F.); +#579=ADVANCED_FACE('',(#57),#561,.F.); +#580=ADVANCED_FACE('',(#58),#562,.F.); +#581=ADVANCED_FACE('',(#59),#563,.F.); +#582=ADVANCED_FACE('',(#60),#564,.F.); +#583=ADVANCED_FACE('',(#61),#565,.F.); +#584=ADVANCED_FACE('',(#62),#566,.F.); +#585=ADVANCED_FACE('',(#63),#567,.F.); +#586=ADVANCED_FACE('',(#64),#568,.F.); +#587=ADVANCED_FACE('',(#65),#569,.F.); +#588=ADVANCED_FACE('',(#66),#570,.T.); +#589=ADVANCED_FACE('',(#67),#571,.F.); +#590=ADVANCED_FACE('',(#68),#39,.F.); +#591=ADVANCED_FACE('',(#69,#15,#16,#17,#18,#19,#20,#21),#40,.F.); +#592=ADVANCED_FACE('',(#70),#41,.F.); +#593=ADVANCED_FACE('',(#71,#22,#23,#24,#25,#26,#27,#28),#42,.T.); +#594=ADVANCED_FACE('',(#72,#29,#30,#31,#32,#33),#43,.F.); +#595=ADVANCED_FACE('',(#73),#572,.T.); +#596=ADVANCED_FACE('',(#74),#573,.F.); +#597=ADVANCED_FACE('',(#75),#44,.T.); +#598=ADVANCED_FACE('',(#76,#34,#35,#36,#37,#38),#45,.T.); +#599=ADVANCED_FACE('',(#77),#574,.T.); +#600=ADVANCED_FACE('',(#78),#575,.T.); +#601=ADVANCED_FACE('',(#79),#46,.F.); +#602=ADVANCED_FACE('',(#80),#576,.F.); +#603=ADVANCED_FACE('',(#81),#47,.F.); +#604=ADVANCED_FACE('',(#82),#48,.F.); +#605=ADVANCED_FACE('',(#83),#49,.F.); +#606=ADVANCED_FACE('',(#84),#50,.F.); +#607=ADVANCED_FACE('',(#85),#51,.F.); +#608=ADVANCED_FACE('',(#86),#52,.F.); +#609=ADVANCED_FACE('',(#87),#53,.F.); +#610=ADVANCED_FACE('',(#88),#54,.F.); +#611=CLOSED_SHELL('',(#577,#578,#579,#580,#581,#582,#583,#584,#585,#586, +#587,#588,#589,#590,#591,#592,#593,#594,#595,#596,#597,#598,#599,#600,#601, +#602,#603,#604,#605,#606,#607,#608,#609,#610)); +#612=DERIVED_UNIT_ELEMENT(#614,1.); +#613=DERIVED_UNIT_ELEMENT(#1049,-3.); +#614=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT(.KILO.,.GRAM.) +); +#615=DERIVED_UNIT((#612,#613)); +#616=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(7850.),#615); +#617=PROPERTY_DEFINITION_REPRESENTATION(#622,#619); +#618=PROPERTY_DEFINITION_REPRESENTATION(#623,#620); +#619=REPRESENTATION('material name',(#621),#1046); +#620=REPRESENTATION('density',(#616),#1046); +#621=DESCRIPTIVE_REPRESENTATION_ITEM('Steel','Steel'); +#622=PROPERTY_DEFINITION('material property','material name',#1056); +#623=PROPERTY_DEFINITION('material property','density of part',#1056); +#624=AXIS2_PLACEMENT_3D('',#881,#695,#696); +#625=AXIS2_PLACEMENT_3D('',#882,#697,#698); +#626=AXIS2_PLACEMENT_3D('',#884,#699,#700); +#627=AXIS2_PLACEMENT_3D('',#887,#702,#703); +#628=AXIS2_PLACEMENT_3D('',#888,#704,#705); +#629=AXIS2_PLACEMENT_3D('',#890,#706,#707); +#630=AXIS2_PLACEMENT_3D('',#893,#709,#710); +#631=AXIS2_PLACEMENT_3D('',#894,#711,#712); +#632=AXIS2_PLACEMENT_3D('',#896,#713,#714); +#633=AXIS2_PLACEMENT_3D('',#899,#716,#717); +#634=AXIS2_PLACEMENT_3D('',#900,#718,#719); +#635=AXIS2_PLACEMENT_3D('',#902,#720,#721); +#636=AXIS2_PLACEMENT_3D('',#905,#723,#724); +#637=AXIS2_PLACEMENT_3D('',#906,#725,#726); +#638=AXIS2_PLACEMENT_3D('',#908,#727,#728); +#639=AXIS2_PLACEMENT_3D('',#911,#730,#731); +#640=AXIS2_PLACEMENT_3D('',#912,#732,#733); +#641=AXIS2_PLACEMENT_3D('',#914,#734,#735); +#642=AXIS2_PLACEMENT_3D('',#917,#737,#738); +#643=AXIS2_PLACEMENT_3D('',#918,#739,#740); +#644=AXIS2_PLACEMENT_3D('',#920,#741,#742); +#645=AXIS2_PLACEMENT_3D('',#923,#744,#745); +#646=AXIS2_PLACEMENT_3D('',#924,#746,#747); +#647=AXIS2_PLACEMENT_3D('',#926,#748,#749); +#648=AXIS2_PLACEMENT_3D('',#929,#751,#752); +#649=AXIS2_PLACEMENT_3D('',#930,#753,#754); +#650=AXIS2_PLACEMENT_3D('',#932,#755,#756); +#651=AXIS2_PLACEMENT_3D('',#935,#758,#759); +#652=AXIS2_PLACEMENT_3D('',#936,#760,#761); +#653=AXIS2_PLACEMENT_3D('',#938,#762,#763); +#654=AXIS2_PLACEMENT_3D('',#941,#765,#766); +#655=AXIS2_PLACEMENT_3D('',#942,#767,#768); +#656=AXIS2_PLACEMENT_3D('',#944,#769,#770); +#657=AXIS2_PLACEMENT_3D('',#947,#772,#773); +#658=AXIS2_PLACEMENT_3D('',#948,#774,#775); +#659=AXIS2_PLACEMENT_3D('',#951,#776,#777); +#660=AXIS2_PLACEMENT_3D('',#955,#779,#780); +#661=AXIS2_PLACEMENT_3D('',#957,#782,#783); +#662=AXIS2_PLACEMENT_3D('',#959,#784,#785); +#663=AXIS2_PLACEMENT_3D('',#962,#787,#788); +#664=AXIS2_PLACEMENT_3D('',#963,#789,#790); +#665=AXIS2_PLACEMENT_3D('',#969,#794,#795); +#666=AXIS2_PLACEMENT_3D('',#973,#798,#799); +#667=AXIS2_PLACEMENT_3D('',#977,#802,#803); +#668=AXIS2_PLACEMENT_3D('',#979,#805,#806); +#669=AXIS2_PLACEMENT_3D('',#982,#807,#808); +#670=AXIS2_PLACEMENT_3D('',#988,#812,#813); +#671=AXIS2_PLACEMENT_3D('',#991,#814,#815); +#672=AXIS2_PLACEMENT_3D('',#994,#818,#819); +#673=AXIS2_PLACEMENT_3D('',#997,#820,#821); +#674=AXIS2_PLACEMENT_3D('',#1001,#823,#824); +#675=AXIS2_PLACEMENT_3D('',#1003,#826,#827); +#676=AXIS2_PLACEMENT_3D('',#1009,#831,#832); +#677=AXIS2_PLACEMENT_3D('',#1012,#835,#836); +#678=AXIS2_PLACEMENT_3D('',#1013,#837,#838); +#679=AXIS2_PLACEMENT_3D('',#1014,#839,#840); +#680=AXIS2_PLACEMENT_3D('',#1015,#841,#842); +#681=AXIS2_PLACEMENT_3D('',#1017,#843,#844); +#682=AXIS2_PLACEMENT_3D('',#1020,#846,#847); +#683=AXIS2_PLACEMENT_3D('',#1021,#848,#849); +#684=AXIS2_PLACEMENT_3D('',#1027,#853,#854); +#685=AXIS2_PLACEMENT_3D('',#1028,#855,#856); +#686=AXIS2_PLACEMENT_3D('',#1029,#857,#858); +#687=AXIS2_PLACEMENT_3D('',#1030,#859,#860); +#688=AXIS2_PLACEMENT_3D('',#1033,#863,#864); +#689=AXIS2_PLACEMENT_3D('',#1036,#867,#868); +#690=AXIS2_PLACEMENT_3D('',#1038,#870,#871); +#691=AXIS2_PLACEMENT_3D('',#1040,#873,#874); +#692=AXIS2_PLACEMENT_3D('',#1041,#875,#876); +#693=AXIS2_PLACEMENT_3D('',#1042,#877,#878); +#694=AXIS2_PLACEMENT_3D('',#1043,#879,#880); +#695=DIRECTION('axis',(0.,0.,1.)); +#696=DIRECTION('refdir',(1.,0.,0.)); +#697=DIRECTION('center_axis',(-1.,0.,0.)); +#698=DIRECTION('ref_axis',(0.,0.,-1.)); +#699=DIRECTION('center_axis',(-1.,0.,0.)); +#700=DIRECTION('ref_axis',(0.,0.,-1.)); +#701=DIRECTION('',(-1.,0.,0.)); +#702=DIRECTION('center_axis',(1.,0.,0.)); +#703=DIRECTION('ref_axis',(0.,0.,-1.)); +#704=DIRECTION('center_axis',(-1.,0.,0.)); +#705=DIRECTION('ref_axis',(0.,1.,0.)); +#706=DIRECTION('center_axis',(-1.,0.,0.)); +#707=DIRECTION('ref_axis',(0.,1.,0.)); +#708=DIRECTION('',(-1.,0.,0.)); +#709=DIRECTION('center_axis',(1.,0.,0.)); +#710=DIRECTION('ref_axis',(0.,1.,0.)); +#711=DIRECTION('center_axis',(-1.,0.,0.)); +#712=DIRECTION('ref_axis',(0.,1.,0.)); +#713=DIRECTION('center_axis',(-1.,0.,0.)); +#714=DIRECTION('ref_axis',(0.,1.,0.)); +#715=DIRECTION('',(-1.,0.,0.)); +#716=DIRECTION('center_axis',(1.,0.,0.)); +#717=DIRECTION('ref_axis',(0.,1.,0.)); +#718=DIRECTION('center_axis',(-1.,0.,0.)); +#719=DIRECTION('ref_axis',(0.,1.,0.)); +#720=DIRECTION('center_axis',(-1.,0.,0.)); +#721=DIRECTION('ref_axis',(0.,1.,0.)); +#722=DIRECTION('',(-1.,0.,0.)); +#723=DIRECTION('center_axis',(1.,0.,0.)); +#724=DIRECTION('ref_axis',(0.,1.,0.)); +#725=DIRECTION('center_axis',(-1.,0.,0.)); +#726=DIRECTION('ref_axis',(0.,1.,0.)); +#727=DIRECTION('center_axis',(-1.,0.,0.)); +#728=DIRECTION('ref_axis',(0.,1.,0.)); +#729=DIRECTION('',(-1.,0.,0.)); +#730=DIRECTION('center_axis',(1.,0.,0.)); +#731=DIRECTION('ref_axis',(0.,1.,0.)); +#732=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#733=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#734=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#735=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#736=DIRECTION('',(-0.999390827019096,0.,0.0348994967025011)); +#737=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#738=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#739=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#740=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#741=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#742=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#743=DIRECTION('',(-0.999390827019096,0.,0.0348994967025011)); +#744=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#745=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#746=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#747=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#748=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#749=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#750=DIRECTION('',(-0.999390827019096,0.,0.0348994967025011)); +#751=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#752=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#753=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#754=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#755=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#756=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#757=DIRECTION('',(-0.999390827019096,0.,0.0348994967025011)); +#758=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#759=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#760=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#761=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#762=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#763=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#764=DIRECTION('',(-0.999390827019096,0.,0.0348994967025011)); +#765=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#766=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#767=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#768=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#769=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#770=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#771=DIRECTION('',(-0.999390827019096,0.,0.0348994967025011)); +#772=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#773=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#774=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#775=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#776=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#777=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#778=DIRECTION('',(0.999390827019096,0.,-0.0348994967025011)); +#779=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#780=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#781=DIRECTION('',(0.999390827019096,0.,-0.0348994967025011)); +#782=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#783=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#784=DIRECTION('center_axis',(-0.999390827019096,0.,0.0348994967025011)); +#785=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#786=DIRECTION('',(-0.999390827019096,0.,0.0348994967025011)); +#787=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#788=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#789=DIRECTION('center_axis',(0.,-1.,0.)); +#790=DIRECTION('ref_axis',(0.,0.,-1.)); +#791=DIRECTION('',(-0.0348994967025011,0.,-0.999390827019096)); +#792=DIRECTION('',(0.999390827019096,0.,-0.0348994967025005)); +#793=DIRECTION('',(-0.0348994967025011,0.,-0.999390827019096)); +#794=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#795=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#796=DIRECTION('',(-0.034899496702501,0.,-0.999390827019096)); +#797=DIRECTION('',(0.,1.,0.)); +#798=DIRECTION('center_axis',(0.,1.,0.)); +#799=DIRECTION('ref_axis',(0.,0.,1.)); +#800=DIRECTION('',(-0.034899496702501,0.,-0.999390827019096)); +#801=DIRECTION('',(0.999390827019096,0.,-0.0348994967025009)); +#802=DIRECTION('center_axis',(0.999390827019096,0.,-0.0348994967025011)); +#803=DIRECTION('ref_axis',(-0.0348994967025011,0.,-0.999390827019096)); +#804=DIRECTION('',(0.,1.,0.)); +#805=DIRECTION('center_axis',(1.,0.,0.)); +#806=DIRECTION('ref_axis',(0.,0.,-1.)); +#807=DIRECTION('center_axis',(1.,0.,0.)); +#808=DIRECTION('ref_axis',(0.,0.707106781186548,0.707106781186548)); +#809=DIRECTION('',(0.,0.,-1.)); +#810=DIRECTION('',(0.,-1.,0.)); +#811=DIRECTION('',(2.73910036535074E-33,0.,-1.)); +#812=DIRECTION('center_axis',(1.,0.,0.)); +#813=DIRECTION('ref_axis',(0.,0.707106781186548,0.707106781186548)); +#814=DIRECTION('center_axis',(-1.,0.,0.)); +#815=DIRECTION('ref_axis',(0.,0.707106781186548,0.707106781186548)); +#816=DIRECTION('',(-1.,0.,0.)); +#817=DIRECTION('',(1.,0.,0.)); +#818=DIRECTION('center_axis',(0.,1.,0.)); +#819=DIRECTION('ref_axis',(-0.927183854566788,0.,-0.37460659341591)); +#820=DIRECTION('center_axis',(0.,1.,0.)); +#821=DIRECTION('ref_axis',(-0.927183854566789,0.,-0.374606593415909)); +#822=DIRECTION('',(0.,-1.,0.)); +#823=DIRECTION('center_axis',(0.,-1.,0.)); +#824=DIRECTION('ref_axis',(-0.927183854566789,0.,-0.374606593415909)); +#825=DIRECTION('',(0.,1.,0.)); +#826=DIRECTION('center_axis',(0.719339800338653,0.,0.694658370458995)); +#827=DIRECTION('ref_axis',(0.694658370458995,0.,-0.719339800338653)); +#828=DIRECTION('',(0.694658370458995,0.,-0.719339800338653)); +#829=DIRECTION('',(0.,-1.,0.)); +#830=DIRECTION('',(0.694658370458995,0.,-0.719339800338653)); +#831=DIRECTION('center_axis',(1.,0.,0.)); +#832=DIRECTION('ref_axis',(0.,0.,-1.)); +#833=DIRECTION('',(2.73910036535074E-33,0.,-1.)); +#834=DIRECTION('',(0.,0.,-1.)); +#835=DIRECTION('center_axis',(0.,1.,0.)); +#836=DIRECTION('ref_axis',(0.93358042649721,0.,0.358367949545278)); +#837=DIRECTION('center_axis',(0.,-1.,0.)); +#838=DIRECTION('ref_axis',(0.933580426497213,0.,0.358367949545272)); +#839=DIRECTION('center_axis',(0.,1.,0.)); +#840=DIRECTION('ref_axis',(0.933580426497213,0.,0.358367949545272)); +#841=DIRECTION('center_axis',(0.,1.,0.)); +#842=DIRECTION('ref_axis',(-0.927183854566788,0.,-0.37460659341591)); +#843=DIRECTION('center_axis',(0.,1.,0.)); +#844=DIRECTION('ref_axis',(-0.927183854566788,0.,-0.37460659341591)); +#845=DIRECTION('',(0.,1.,0.)); +#846=DIRECTION('center_axis',(0.,-1.,0.)); +#847=DIRECTION('ref_axis',(-0.927183854566788,0.,-0.37460659341591)); +#848=DIRECTION('center_axis',(0.719339800338653,0.,0.694658370458995)); +#849=DIRECTION('ref_axis',(0.694658370458995,0.,-0.719339800338653)); +#850=DIRECTION('',(0.694658370458995,0.,-0.719339800338653)); +#851=DIRECTION('',(0.,-1.,0.)); +#852=DIRECTION('',(0.694658370458995,0.,-0.719339800338653)); +#853=DIRECTION('center_axis',(0.,1.,0.)); +#854=DIRECTION('ref_axis',(0.93358042649721,0.,0.358367949545278)); +#855=DIRECTION('center_axis',(0.,-1.,0.)); +#856=DIRECTION('ref_axis',(0.933580426497213,0.,0.358367949545272)); +#857=DIRECTION('center_axis',(0.,1.,0.)); +#858=DIRECTION('ref_axis',(0.933580426497213,0.,0.358367949545272)); +#859=DIRECTION('center_axis',(0.,-1.,0.)); +#860=DIRECTION('ref_axis',(0.,0.,-1.)); +#861=DIRECTION('',(1.,0.,0.)); +#862=DIRECTION('',(0.719339800338653,0.,0.694658370458995)); +#863=DIRECTION('center_axis',(0.,1.,0.)); +#864=DIRECTION('ref_axis',(0.,0.,1.)); +#865=DIRECTION('',(0.719339800338653,0.,0.694658370458995)); +#866=DIRECTION('',(1.,0.,0.)); +#867=DIRECTION('center_axis',(0.,1.,0.)); +#868=DIRECTION('ref_axis',(0.,0.,1.)); +#869=DIRECTION('',(0.719339800338669,0.,0.694658370458978)); +#870=DIRECTION('center_axis',(0.,-1.,0.)); +#871=DIRECTION('ref_axis',(0.,0.,-1.)); +#872=DIRECTION('',(0.719339800338669,0.,0.694658370458978)); +#873=DIRECTION('center_axis',(0.,-1.,0.)); +#874=DIRECTION('ref_axis',(0.,0.,-1.)); +#875=DIRECTION('center_axis',(0.,1.,0.)); +#876=DIRECTION('ref_axis',(0.,0.,1.)); +#877=DIRECTION('center_axis',(0.,-1.,0.)); +#878=DIRECTION('ref_axis',(0.,0.,-1.)); +#879=DIRECTION('center_axis',(0.,1.,0.)); +#880=DIRECTION('ref_axis',(0.,0.,1.)); +#881=CARTESIAN_POINT('',(0.,0.,0.)); +#882=CARTESIAN_POINT('Origin',(2.5,17.5,0.)); +#883=CARTESIAN_POINT('',(2.5,17.5,7.)); +#884=CARTESIAN_POINT('Origin',(2.5,17.5,0.)); +#885=CARTESIAN_POINT('',(0.,17.5,7.)); +#886=CARTESIAN_POINT('',(2.5,17.5,7.)); +#887=CARTESIAN_POINT('Origin',(0.,17.5,0.)); +#888=CARTESIAN_POINT('Origin',(-36.,7.95405845398161,-9.54594154601839)); +#889=CARTESIAN_POINT('',(2.5,6.35405845398161,-9.54594154601839)); +#890=CARTESIAN_POINT('Origin',(2.5,7.95405845398161,-9.54594154601839)); +#891=CARTESIAN_POINT('',(0.,6.35405845398161,-9.54594154601839)); +#892=CARTESIAN_POINT('',(-36.,6.35405845398161,-9.54594154601839)); +#893=CARTESIAN_POINT('Origin',(0.,7.95405845398161,-9.54594154601839)); +#894=CARTESIAN_POINT('Origin',(-36.,27.0459415460184,9.54594154601839)); +#895=CARTESIAN_POINT('',(2.5,25.4459415460184,9.54594154601839)); +#896=CARTESIAN_POINT('Origin',(2.5,27.0459415460184,9.54594154601839)); +#897=CARTESIAN_POINT('',(0.,25.4459415460184,9.54594154601839)); +#898=CARTESIAN_POINT('',(-36.,25.4459415460184,9.54594154601839)); +#899=CARTESIAN_POINT('Origin',(0.,27.0459415460184,9.54594154601839)); +#900=CARTESIAN_POINT('Origin',(-36.,7.95405845398161,9.54594154601839)); +#901=CARTESIAN_POINT('',(2.5,6.35405845398161,9.54594154601839)); +#902=CARTESIAN_POINT('Origin',(2.5,7.95405845398161,9.54594154601839)); +#903=CARTESIAN_POINT('',(0.,6.35405845398161,9.54594154601839)); +#904=CARTESIAN_POINT('',(-36.,6.35405845398161,9.54594154601839)); +#905=CARTESIAN_POINT('Origin',(0.,7.95405845398161,9.54594154601839)); +#906=CARTESIAN_POINT('Origin',(-36.,27.0459415460184,-9.54594154601839)); +#907=CARTESIAN_POINT('',(2.5,25.4459415460184,-9.54594154601839)); +#908=CARTESIAN_POINT('Origin',(2.5,27.0459415460184,-9.54594154601839)); +#909=CARTESIAN_POINT('',(0.,25.4459415460184,-9.54594154601839)); +#910=CARTESIAN_POINT('',(-36.,25.4459415460184,-9.54594154601839)); +#911=CARTESIAN_POINT('Origin',(0.,27.0459415460184,-9.54594154601839)); +#912=CARTESIAN_POINT('Origin',(19.4958512574805,24.25,-96.9297481203633)); +#913=CARTESIAN_POINT('',(19.5516904522045,24.25,-95.3307227971327)); +#914=CARTESIAN_POINT('Origin',(19.4958512574805,24.25,-96.9297481203633)); +#915=CARTESIAN_POINT('',(17.0532133846568,24.25,-95.2434740553765)); +#916=CARTESIAN_POINT('',(19.5516904522045,24.25,-95.3307227971327)); +#917=CARTESIAN_POINT('Origin',(16.9973741899327,24.25,-96.842499378607)); +#918=CARTESIAN_POINT('Origin',(20.3118952270192,24.25,-73.561306318656)); +#919=CARTESIAN_POINT('',(20.3677344217432,24.25,-71.9622809954255)); +#920=CARTESIAN_POINT('Origin',(20.3118952270192,24.25,-73.561306318656)); +#921=CARTESIAN_POINT('',(17.8692573541955,24.25,-71.8750322536692)); +#922=CARTESIAN_POINT('',(20.3677344217432,24.25,-71.9622809954255)); +#923=CARTESIAN_POINT('Origin',(17.8134181594715,24.25,-73.4740575768998)); +#924=CARTESIAN_POINT('Origin',(19.4958512574805,10.75,-96.9297481203633)); +#925=CARTESIAN_POINT('',(19.5516904522045,10.75,-95.3307227971327)); +#926=CARTESIAN_POINT('Origin',(19.4958512574805,10.75,-96.9297481203633)); +#927=CARTESIAN_POINT('',(17.0532133846568,10.75,-95.2434740553765)); +#928=CARTESIAN_POINT('',(19.5516904522045,10.75,-95.3307227971327)); +#929=CARTESIAN_POINT('Origin',(16.9973741899327,10.75,-96.842499378607)); +#930=CARTESIAN_POINT('Origin',(19.9038732422499,31.,-85.2455272195096)); +#931=CARTESIAN_POINT('',(19.9597124369739,31.,-83.6465018962791)); +#932=CARTESIAN_POINT('Origin',(19.9038732422499,31.,-85.2455272195096)); +#933=CARTESIAN_POINT('',(17.4612353694261,31.,-83.5592531545228)); +#934=CARTESIAN_POINT('',(19.9597124369739,31.,-83.6465018962791)); +#935=CARTESIAN_POINT('Origin',(17.4053961747021,31.,-85.1582784777534)); +#936=CARTESIAN_POINT('Origin',(20.3118952270192,10.75,-73.561306318656)); +#937=CARTESIAN_POINT('',(20.3677344217432,10.75,-71.9622809954255)); +#938=CARTESIAN_POINT('Origin',(20.3118952270192,10.75,-73.561306318656)); +#939=CARTESIAN_POINT('',(17.8692573541955,10.75,-71.8750322536692)); +#940=CARTESIAN_POINT('',(20.3677344217432,10.75,-71.9622809954255)); +#941=CARTESIAN_POINT('Origin',(17.8134181594715,10.75,-73.4740575768998)); +#942=CARTESIAN_POINT('Origin',(19.9038732422499,4.00000000000002,-85.2455272195096)); +#943=CARTESIAN_POINT('',(19.9597124369739,4.00000000000002,-83.6465018962791)); +#944=CARTESIAN_POINT('Origin',(19.9038732422499,4.00000000000002,-85.2455272195096)); +#945=CARTESIAN_POINT('',(17.4612353694261,4.00000000000002,-83.5592531545228)); +#946=CARTESIAN_POINT('',(19.9597124369739,4.00000000000002,-83.6465018962791)); +#947=CARTESIAN_POINT('Origin',(17.4053961747021,4.00000000000002,-85.1582784777534)); +#948=CARTESIAN_POINT('Origin',(19.9038732422499,17.5,-85.2455272195096)); +#949=CARTESIAN_POINT('',(17.4053961747021,35.,-85.1582784777534)); +#950=CARTESIAN_POINT('',(17.4053961747021,0.,-85.1582784777534)); +#951=CARTESIAN_POINT('Origin',(17.4053961747021,17.5,-85.1582784777534)); +#952=CARTESIAN_POINT('',(19.9038732422499,35.,-85.2455272195096)); +#953=CARTESIAN_POINT('',(19.9038732422499,35.,-85.2455272195096)); +#954=CARTESIAN_POINT('',(19.9038732422499,0.,-85.2455272195096)); +#955=CARTESIAN_POINT('Origin',(19.9038732422499,17.5,-85.2455272195096)); +#956=CARTESIAN_POINT('',(19.9038732422499,0.,-85.2455272195096)); +#957=CARTESIAN_POINT('Origin',(19.9038732422499,17.5,-85.2455272195096)); +#958=CARTESIAN_POINT('',(20.1481697191674,17.5,-78.249791430376)); +#959=CARTESIAN_POINT('Origin',(19.9038732422499,17.5,-85.2455272195096)); +#960=CARTESIAN_POINT('',(17.6496926516196,17.5,-78.1625426886197)); +#961=CARTESIAN_POINT('',(20.1481697191674,17.5,-78.249791430376)); +#962=CARTESIAN_POINT('Origin',(17.4053961747021,17.5,-85.1582784777534)); +#963=CARTESIAN_POINT('Origin',(17.8514213838668,35.,-72.3857876175495)); +#964=CARTESIAN_POINT('',(18.9081877853252,35.,-42.1239572845115)); +#965=CARTESIAN_POINT('',(18.0161373669959,35.,-67.6689390049192)); +#966=CARTESIAN_POINT('',(21.4066648528729,35.,-42.2112060262677)); +#967=CARTESIAN_POINT('',(18.9081877853252,35.,-42.1239572845115)); +#968=CARTESIAN_POINT('',(20.5146144345436,35.,-67.7561877466755)); +#969=CARTESIAN_POINT('Origin',(18.90966918107,0.,-42.0815356607494)); +#970=CARTESIAN_POINT('',(18.9081877853252,0.,-42.1239572845115)); +#971=CARTESIAN_POINT('',(18.0161373669959,0.,-67.6689390049192)); +#972=CARTESIAN_POINT('',(18.9081877853252,0.,-42.1239572845115)); +#973=CARTESIAN_POINT('Origin',(17.8514213838668,0.,-72.3857876175495)); +#974=CARTESIAN_POINT('',(21.4066648528729,0.,-42.2112060262677)); +#975=CARTESIAN_POINT('',(20.5146144345436,0.,-67.7561877466755)); +#976=CARTESIAN_POINT('',(18.9081877853252,0.,-42.1239572845115)); +#977=CARTESIAN_POINT('Origin',(21.4081462486178,0.,-42.1687844025057)); +#978=CARTESIAN_POINT('',(21.4066648528729,0.,-42.2112060262677)); +#979=CARTESIAN_POINT('Origin',(0.,0.,17.5)); +#980=CARTESIAN_POINT('',(0.,35.,0.)); +#981=CARTESIAN_POINT('',(0.,0.,0.)); +#982=CARTESIAN_POINT('Origin',(0.,17.5,0.)); +#983=CARTESIAN_POINT('',(0.,35.,-21.4495318128286)); +#984=CARTESIAN_POINT('',(0.,35.,0.)); +#985=CARTESIAN_POINT('',(5.8752420425121E-32,0.,-21.4495318128286)); +#986=CARTESIAN_POINT('',(0.,0.,-21.4495318128286)); +#987=CARTESIAN_POINT('',(0.,0.,0.)); +#988=CARTESIAN_POINT('Origin',(0.,17.5,0.)); +#989=CARTESIAN_POINT('',(2.5,0.,0.)); +#990=CARTESIAN_POINT('',(2.5,35.,0.)); +#991=CARTESIAN_POINT('Origin',(2.5,17.5,0.)); +#992=CARTESIAN_POINT('',(0.,35.,0.)); +#993=CARTESIAN_POINT('',(2.70454100787079E-33,0.,0.)); +#994=CARTESIAN_POINT('Origin',(2.6,0.,-21.4495318128286)); +#995=CARTESIAN_POINT('',(2.52806601996614,35.,-21.5189976498745)); +#996=CARTESIAN_POINT('',(2.5,35.,-21.4495318128286)); +#997=CARTESIAN_POINT('Origin',(2.6,35.,-21.4495318128286)); +#998=CARTESIAN_POINT('',(2.5,0.,-21.4495318128286)); +#999=CARTESIAN_POINT('',(2.5,0.,-21.4495318128286)); +#1000=CARTESIAN_POINT('',(2.52806601996614,0.,-21.5189976498745)); +#1001=CARTESIAN_POINT('Origin',(2.6,0.,-21.4495318128286)); +#1002=CARTESIAN_POINT('',(2.52806601996614,0.,-21.5189976498745)); +#1003=CARTESIAN_POINT('Origin',(1.79834950084663,0.,-20.7633540738525)); +#1004=CARTESIAN_POINT('',(20.6785321835038,0.,-40.3143555716479)); +#1005=CARTESIAN_POINT('',(1.79834950084663,0.,-20.7633540738525)); +#1006=CARTESIAN_POINT('',(20.6785321835038,35.,-40.3143555716479)); +#1007=CARTESIAN_POINT('',(20.6785321835037,0.,-40.3143555716478)); +#1008=CARTESIAN_POINT('',(1.79834950084663,35.,-20.7633540738525)); +#1009=CARTESIAN_POINT('Origin',(2.5,0.,17.5)); +#1010=CARTESIAN_POINT('',(2.5,0.,0.)); +#1011=CARTESIAN_POINT('',(2.5,35.,0.)); +#1012=CARTESIAN_POINT('Origin',(18.8082487026232,0.,-42.1204673348412)); +#1013=CARTESIAN_POINT('Origin',(18.8082487026232,35.,-42.1204673348412)); +#1014=CARTESIAN_POINT('Origin',(18.8082487026232,0.,-42.1204673348412)); +#1015=CARTESIAN_POINT('Origin',(2.6,0.,-21.4495318128286)); +#1016=CARTESIAN_POINT('',(0.729716519119503,35.,-23.255643576022)); +#1017=CARTESIAN_POINT('Origin',(2.6,35.,-21.4495318128286)); +#1018=CARTESIAN_POINT('',(0.729716519119503,0.,-23.255643576022)); +#1019=CARTESIAN_POINT('',(0.729716519119504,0.,-23.255643576022)); +#1020=CARTESIAN_POINT('Origin',(2.6,0.,-21.4495318128286)); +#1021=CARTESIAN_POINT('Origin',(6.16297582203915E-32,0.,-22.5)); +#1022=CARTESIAN_POINT('',(18.8801826826571,35.,-42.0510014977953)); +#1023=CARTESIAN_POINT('',(6.16297582203915E-32,35.,-22.5)); +#1024=CARTESIAN_POINT('',(18.8801826826571,0.,-42.0510014977953)); +#1025=CARTESIAN_POINT('',(18.8801826826571,0.,-42.0510014977953)); +#1026=CARTESIAN_POINT('',(6.16297582203915E-32,0.,-22.5)); +#1027=CARTESIAN_POINT('Origin',(18.8082487026232,0.,-42.1204673348412)); +#1028=CARTESIAN_POINT('Origin',(18.8082487026232,35.,-42.1204673348412)); +#1029=CARTESIAN_POINT('Origin',(18.8082487026232,0.,-42.1204673348412)); +#1030=CARTESIAN_POINT('Origin',(0.189321978126352,35.,-22.42350895571)); +#1031=CARTESIAN_POINT('',(0.,35.,-21.4495318128286)); +#1032=CARTESIAN_POINT('',(0.729716519119503,35.,-23.255643576022)); +#1033=CARTESIAN_POINT('Origin',(0.189321978126352,0.,-22.42350895571)); +#1034=CARTESIAN_POINT('',(0.729716519119503,0.,-23.255643576022)); +#1035=CARTESIAN_POINT('',(5.8752420425121E-32,0.,-21.4495318128286)); +#1036=CARTESIAN_POINT('Origin',(9.80494960088831,0.,-32.6533225369086)); +#1037=CARTESIAN_POINT('',(18.8801826826571,0.,-42.0510014977953)); +#1038=CARTESIAN_POINT('Origin',(9.80494960088831,35.,-32.6533225369086)); +#1039=CARTESIAN_POINT('',(18.8801826826571,35.,-42.0510014977953)); +#1040=CARTESIAN_POINT('Origin',(0.,35.,-1.9747659064143)); +#1041=CARTESIAN_POINT('Origin',(5.40908201574158E-33,0.,-1.9747659064143)); +#1042=CARTESIAN_POINT('Origin',(18.901606745273,35.,-42.0846305398867)); +#1043=CARTESIAN_POINT('Origin',(18.901606745273,0.,-42.0846305398867)); +#1044=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1048, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1045=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1048, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1046=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1044)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1048,#1050,#1051)) +REPRESENTATION_CONTEXT('','3D') +); +#1047=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1045)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1048,#1050,#1051)) +REPRESENTATION_CONTEXT('','3D') +); +#1048=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#1049=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT($,.METRE.) +); +#1050=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#1051=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#1052=SHAPE_DEFINITION_REPRESENTATION(#1053,#1054); +#1053=PRODUCT_DEFINITION_SHAPE('',$,#1056); +#1054=SHAPE_REPRESENTATION('',(#624),#1046); +#1055=PRODUCT_DEFINITION_CONTEXT('part definition',#1060,'design'); +#1056=PRODUCT_DEFINITION('link3-4-1 (angestellt)', +'link3-4-1 (angestellt) v2',#1057,#1055); +#1057=PRODUCT_DEFINITION_FORMATION('',$,#1062); +#1058=PRODUCT_RELATED_PRODUCT_CATEGORY('link3-4-1 (angestellt) v2', +'link3-4-1 (angestellt) v2',(#1062)); +#1059=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#1060); +#1060=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#1061=PRODUCT_CONTEXT('part definition',#1060,'mechanical'); +#1062=PRODUCT('link3-4-1 (angestellt)','link3-4-1 (angestellt) v2',$,(#1061)); +#1063=PRESENTATION_STYLE_ASSIGNMENT((#1065)); +#1064=PRESENTATION_STYLE_ASSIGNMENT((#1066)); +#1065=SURFACE_STYLE_USAGE(.BOTH.,#1067); +#1066=SURFACE_STYLE_USAGE(.BOTH.,#1068); +#1067=SURFACE_SIDE_STYLE('',(#1069)); +#1068=SURFACE_SIDE_STYLE('',(#1070)); +#1069=SURFACE_STYLE_FILL_AREA(#1071); +#1070=SURFACE_STYLE_FILL_AREA(#1072); +#1071=FILL_AREA_STYLE('Steel - Satin',(#1073)); +#1072=FILL_AREA_STYLE('Aluminum - Satin',(#1074)); +#1073=FILL_AREA_STYLE_COLOUR('Steel - Satin',#1075); +#1074=FILL_AREA_STYLE_COLOUR('Aluminum - Satin',#1076); +#1075=COLOUR_RGB('Steel - Satin',0.627450980392157,0.627450980392157,0.627450980392157); +#1076=COLOUR_RGB('Aluminum - Satin',0.96078431372549,0.96078431372549,0.964705882352941); +ENDSEC; +END-ISO-10303-21; diff --git a/hardware/follower_STEPs/link3-4-1_v0.2.0.step b/hardware/follower_STEPs/link3-4-1_v0.2.0.step new file mode 100644 index 0000000000000000000000000000000000000000..5286dec478ec3899aa6d32a0fc5dd10b1c6394e8 --- /dev/null +++ b/hardware/follower_STEPs/link3-4-1_v0.2.0.step @@ -0,0 +1,1133 @@ +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 */ 'link3-4-1.step', +/* time_stamp */ '2025-11-24T15:35:48+01:00', +/* author */ (''), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v20.1', +/* originating_system */ 'Autodesk Translation Framework v14.21.0.0', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#1047); +#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#1054,#12); +#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#1046); +#13=STYLED_ITEM('',(#1064),#14); +#14=MANIFOLD_SOLID_BREP('Body1',#611); +#15=FACE_BOUND('',#104,.T.); +#16=FACE_BOUND('',#105,.T.); +#17=FACE_BOUND('',#106,.T.); +#18=FACE_BOUND('',#107,.T.); +#19=FACE_BOUND('',#108,.T.); +#20=FACE_BOUND('',#109,.T.); +#21=FACE_BOUND('',#110,.T.); +#22=FACE_BOUND('',#113,.T.); +#23=FACE_BOUND('',#114,.T.); +#24=FACE_BOUND('',#115,.T.); +#25=FACE_BOUND('',#116,.T.); +#26=FACE_BOUND('',#117,.T.); +#27=FACE_BOUND('',#118,.T.); +#28=FACE_BOUND('',#119,.T.); +#29=FACE_BOUND('',#121,.T.); +#30=FACE_BOUND('',#122,.T.); +#31=FACE_BOUND('',#123,.T.); +#32=FACE_BOUND('',#124,.T.); +#33=FACE_BOUND('',#125,.T.); +#34=FACE_BOUND('',#130,.T.); +#35=FACE_BOUND('',#131,.T.); +#36=FACE_BOUND('',#132,.T.); +#37=FACE_BOUND('',#133,.T.); +#38=FACE_BOUND('',#134,.T.); +#39=PLANE('',#664); +#40=PLANE('',#665); +#41=PLANE('',#666); +#42=PLANE('',#667); +#43=PLANE('',#668); +#44=PLANE('',#675); +#45=PLANE('',#676); +#46=PLANE('',#683); +#47=PLANE('',#687); +#48=PLANE('',#688); +#49=PLANE('',#689); +#50=PLANE('',#690); +#51=PLANE('',#691); +#52=PLANE('',#692); +#53=PLANE('',#693); +#54=PLANE('',#694); +#55=FACE_OUTER_BOUND('',#89,.T.); +#56=FACE_OUTER_BOUND('',#90,.T.); +#57=FACE_OUTER_BOUND('',#91,.T.); +#58=FACE_OUTER_BOUND('',#92,.T.); +#59=FACE_OUTER_BOUND('',#93,.T.); +#60=FACE_OUTER_BOUND('',#94,.T.); +#61=FACE_OUTER_BOUND('',#95,.T.); +#62=FACE_OUTER_BOUND('',#96,.T.); +#63=FACE_OUTER_BOUND('',#97,.T.); +#64=FACE_OUTER_BOUND('',#98,.T.); +#65=FACE_OUTER_BOUND('',#99,.T.); +#66=FACE_OUTER_BOUND('',#100,.T.); +#67=FACE_OUTER_BOUND('',#101,.T.); +#68=FACE_OUTER_BOUND('',#102,.T.); +#69=FACE_OUTER_BOUND('',#103,.T.); +#70=FACE_OUTER_BOUND('',#111,.T.); +#71=FACE_OUTER_BOUND('',#112,.T.); +#72=FACE_OUTER_BOUND('',#120,.T.); +#73=FACE_OUTER_BOUND('',#126,.T.); +#74=FACE_OUTER_BOUND('',#127,.T.); +#75=FACE_OUTER_BOUND('',#128,.T.); +#76=FACE_OUTER_BOUND('',#129,.T.); +#77=FACE_OUTER_BOUND('',#135,.T.); +#78=FACE_OUTER_BOUND('',#136,.T.); +#79=FACE_OUTER_BOUND('',#137,.T.); +#80=FACE_OUTER_BOUND('',#138,.T.); +#81=FACE_OUTER_BOUND('',#139,.T.); +#82=FACE_OUTER_BOUND('',#140,.T.); +#83=FACE_OUTER_BOUND('',#141,.T.); +#84=FACE_OUTER_BOUND('',#142,.T.); +#85=FACE_OUTER_BOUND('',#143,.T.); +#86=FACE_OUTER_BOUND('',#144,.T.); +#87=FACE_OUTER_BOUND('',#145,.T.); +#88=FACE_OUTER_BOUND('',#146,.T.); +#89=EDGE_LOOP('',(#399,#400,#401,#402)); +#90=EDGE_LOOP('',(#403,#404,#405,#406)); +#91=EDGE_LOOP('',(#407,#408,#409,#410)); +#92=EDGE_LOOP('',(#411,#412,#413,#414)); +#93=EDGE_LOOP('',(#415,#416,#417,#418)); +#94=EDGE_LOOP('',(#419,#420,#421,#422)); +#95=EDGE_LOOP('',(#423,#424,#425,#426)); +#96=EDGE_LOOP('',(#427,#428,#429,#430)); +#97=EDGE_LOOP('',(#431,#432,#433,#434)); +#98=EDGE_LOOP('',(#435,#436,#437,#438)); +#99=EDGE_LOOP('',(#439,#440,#441,#442)); +#100=EDGE_LOOP('',(#443,#444,#445,#446)); +#101=EDGE_LOOP('',(#447,#448,#449,#450)); +#102=EDGE_LOOP('',(#451,#452,#453,#454)); +#103=EDGE_LOOP('',(#455,#456,#457,#458)); +#104=EDGE_LOOP('',(#459)); +#105=EDGE_LOOP('',(#460)); +#106=EDGE_LOOP('',(#461)); +#107=EDGE_LOOP('',(#462)); +#108=EDGE_LOOP('',(#463)); +#109=EDGE_LOOP('',(#464)); +#110=EDGE_LOOP('',(#465)); +#111=EDGE_LOOP('',(#466,#467,#468,#469)); +#112=EDGE_LOOP('',(#470,#471,#472,#473)); +#113=EDGE_LOOP('',(#474)); +#114=EDGE_LOOP('',(#475)); +#115=EDGE_LOOP('',(#476)); +#116=EDGE_LOOP('',(#477)); +#117=EDGE_LOOP('',(#478)); +#118=EDGE_LOOP('',(#479)); +#119=EDGE_LOOP('',(#480)); +#120=EDGE_LOOP('',(#481,#482,#483,#484)); +#121=EDGE_LOOP('',(#485)); +#122=EDGE_LOOP('',(#486)); +#123=EDGE_LOOP('',(#487)); +#124=EDGE_LOOP('',(#488)); +#125=EDGE_LOOP('',(#489)); +#126=EDGE_LOOP('',(#490,#491,#492,#493)); +#127=EDGE_LOOP('',(#494,#495,#496,#497)); +#128=EDGE_LOOP('',(#498,#499,#500,#501)); +#129=EDGE_LOOP('',(#502,#503,#504,#505)); +#130=EDGE_LOOP('',(#506)); +#131=EDGE_LOOP('',(#507)); +#132=EDGE_LOOP('',(#508)); +#133=EDGE_LOOP('',(#509)); +#134=EDGE_LOOP('',(#510)); +#135=EDGE_LOOP('',(#511,#512,#513,#514)); +#136=EDGE_LOOP('',(#515,#516,#517,#518)); +#137=EDGE_LOOP('',(#519,#520,#521,#522)); +#138=EDGE_LOOP('',(#523,#524,#525,#526)); +#139=EDGE_LOOP('',(#527,#528,#529,#530)); +#140=EDGE_LOOP('',(#531,#532,#533,#534)); +#141=EDGE_LOOP('',(#535,#536,#537,#538)); +#142=EDGE_LOOP('',(#539,#540,#541,#542)); +#143=EDGE_LOOP('',(#543,#544,#545,#546)); +#144=EDGE_LOOP('',(#547,#548,#549,#550)); +#145=EDGE_LOOP('',(#551,#552,#553,#554)); +#146=EDGE_LOOP('',(#555,#556,#557,#558)); +#147=LINE('',#886,#191); +#148=LINE('',#892,#192); +#149=LINE('',#898,#193); +#150=LINE('',#904,#194); +#151=LINE('',#910,#195); +#152=LINE('',#916,#196); +#153=LINE('',#922,#197); +#154=LINE('',#928,#198); +#155=LINE('',#935,#199); +#156=LINE('',#938,#200); +#157=LINE('',#943,#201); +#158=LINE('',#949,#202); +#159=LINE('',#955,#203); +#160=LINE('',#961,#204); +#161=LINE('',#965,#205); +#162=LINE('',#967,#206); +#163=LINE('',#968,#207); +#164=LINE('',#971,#208); +#165=LINE('',#972,#209); +#166=LINE('',#975,#210); +#167=LINE('',#976,#211); +#168=LINE('',#978,#212); +#169=LINE('',#984,#213); +#170=LINE('',#986,#214); +#171=LINE('',#987,#215); +#172=LINE('',#992,#216); +#173=LINE('',#993,#217); +#174=LINE('',#999,#218); +#175=LINE('',#1002,#219); +#176=LINE('',#1005,#220); +#177=LINE('',#1007,#221); +#178=LINE('',#1008,#222); +#179=LINE('',#1010,#223); +#180=LINE('',#1011,#224); +#181=LINE('',#1019,#225); +#182=LINE('',#1023,#226); +#183=LINE('',#1025,#227); +#184=LINE('',#1026,#228); +#185=LINE('',#1031,#229); +#186=LINE('',#1032,#230); +#187=LINE('',#1034,#231); +#188=LINE('',#1035,#232); +#189=LINE('',#1037,#233); +#190=LINE('',#1039,#234); +#191=VECTOR('',#701,1.6); +#192=VECTOR('',#708,1.6); +#193=VECTOR('',#715,1.6); +#194=VECTOR('',#722,1.6); +#195=VECTOR('',#729,1.6); +#196=VECTOR('',#736,1.6); +#197=VECTOR('',#743,1.6); +#198=VECTOR('',#750,7.00000000000001); +#199=VECTOR('',#757,10.); +#200=VECTOR('',#760,10.); +#201=VECTOR('',#765,1.6); +#202=VECTOR('',#772,1.6); +#203=VECTOR('',#779,1.6); +#204=VECTOR('',#786,7.); +#205=VECTOR('',#791,10.); +#206=VECTOR('',#792,10.); +#207=VECTOR('',#793,10.); +#208=VECTOR('',#796,10.); +#209=VECTOR('',#797,10.); +#210=VECTOR('',#800,10.); +#211=VECTOR('',#801,10.); +#212=VECTOR('',#804,10.); +#213=VECTOR('',#809,10.); +#214=VECTOR('',#810,10.); +#215=VECTOR('',#811,10.); +#216=VECTOR('',#816,10.); +#217=VECTOR('',#817,10.); +#218=VECTOR('',#822,10.); +#219=VECTOR('',#825,10.); +#220=VECTOR('',#828,10.); +#221=VECTOR('',#829,10.); +#222=VECTOR('',#830,10.); +#223=VECTOR('',#833,10.); +#224=VECTOR('',#834,10.); +#225=VECTOR('',#845,10.); +#226=VECTOR('',#850,10.); +#227=VECTOR('',#851,10.); +#228=VECTOR('',#852,10.); +#229=VECTOR('',#861,10.); +#230=VECTOR('',#862,10.); +#231=VECTOR('',#865,10.); +#232=VECTOR('',#866,10.); +#233=VECTOR('',#869,10.); +#234=VECTOR('',#872,10.); +#235=CIRCLE('',#626,1.6); +#236=CIRCLE('',#627,1.6); +#237=CIRCLE('',#629,1.6); +#238=CIRCLE('',#630,1.6); +#239=CIRCLE('',#632,1.6); +#240=CIRCLE('',#633,1.6); +#241=CIRCLE('',#635,1.6); +#242=CIRCLE('',#636,1.6); +#243=CIRCLE('',#638,1.6); +#244=CIRCLE('',#639,1.6); +#245=CIRCLE('',#641,1.6); +#246=CIRCLE('',#642,1.6); +#247=CIRCLE('',#644,1.6); +#248=CIRCLE('',#645,1.6); +#249=CIRCLE('',#647,7.00000000000001); +#250=CIRCLE('',#648,7.00000000000001); +#251=CIRCLE('',#650,17.5); +#252=CIRCLE('',#651,17.5); +#253=CIRCLE('',#653,1.6); +#254=CIRCLE('',#654,1.6); +#255=CIRCLE('',#656,1.6); +#256=CIRCLE('',#657,1.6); +#257=CIRCLE('',#659,1.6); +#258=CIRCLE('',#660,1.6); +#259=CIRCLE('',#662,7.); +#260=CIRCLE('',#663,7.); +#261=CIRCLE('',#669,17.5); +#262=CIRCLE('',#671,17.5); +#263=CIRCLE('',#673,0.100000000000001); +#264=CIRCLE('',#674,0.100000000000001); +#265=CIRCLE('',#678,2.6); +#266=CIRCLE('',#679,2.6); +#267=CIRCLE('',#681,2.6); +#268=CIRCLE('',#682,2.6); +#269=CIRCLE('',#685,0.100000000000002); +#270=CIRCLE('',#686,0.100000000000002); +#271=VERTEX_POINT('',#883); +#272=VERTEX_POINT('',#885); +#273=VERTEX_POINT('',#889); +#274=VERTEX_POINT('',#891); +#275=VERTEX_POINT('',#895); +#276=VERTEX_POINT('',#897); +#277=VERTEX_POINT('',#901); +#278=VERTEX_POINT('',#903); +#279=VERTEX_POINT('',#907); +#280=VERTEX_POINT('',#909); +#281=VERTEX_POINT('',#913); +#282=VERTEX_POINT('',#915); +#283=VERTEX_POINT('',#919); +#284=VERTEX_POINT('',#921); +#285=VERTEX_POINT('',#925); +#286=VERTEX_POINT('',#927); +#287=VERTEX_POINT('',#931); +#288=VERTEX_POINT('',#932); +#289=VERTEX_POINT('',#934); +#290=VERTEX_POINT('',#936); +#291=VERTEX_POINT('',#940); +#292=VERTEX_POINT('',#942); +#293=VERTEX_POINT('',#946); +#294=VERTEX_POINT('',#948); +#295=VERTEX_POINT('',#952); +#296=VERTEX_POINT('',#954); +#297=VERTEX_POINT('',#958); +#298=VERTEX_POINT('',#960); +#299=VERTEX_POINT('',#964); +#300=VERTEX_POINT('',#966); +#301=VERTEX_POINT('',#970); +#302=VERTEX_POINT('',#974); +#303=VERTEX_POINT('',#980); +#304=VERTEX_POINT('',#981); +#305=VERTEX_POINT('',#983); +#306=VERTEX_POINT('',#985); +#307=VERTEX_POINT('',#989); +#308=VERTEX_POINT('',#990); +#309=VERTEX_POINT('',#995); +#310=VERTEX_POINT('',#996); +#311=VERTEX_POINT('',#998); +#312=VERTEX_POINT('',#1000); +#313=VERTEX_POINT('',#1004); +#314=VERTEX_POINT('',#1006); +#315=VERTEX_POINT('',#1016); +#316=VERTEX_POINT('',#1018); +#317=VERTEX_POINT('',#1022); +#318=VERTEX_POINT('',#1024); +#319=EDGE_CURVE('',#271,#271,#235,.T.); +#320=EDGE_CURVE('',#271,#272,#147,.T.); +#321=EDGE_CURVE('',#272,#272,#236,.T.); +#322=EDGE_CURVE('',#273,#273,#237,.T.); +#323=EDGE_CURVE('',#273,#274,#148,.T.); +#324=EDGE_CURVE('',#274,#274,#238,.T.); +#325=EDGE_CURVE('',#275,#275,#239,.T.); +#326=EDGE_CURVE('',#275,#276,#149,.T.); +#327=EDGE_CURVE('',#276,#276,#240,.T.); +#328=EDGE_CURVE('',#277,#277,#241,.T.); +#329=EDGE_CURVE('',#277,#278,#150,.T.); +#330=EDGE_CURVE('',#278,#278,#242,.T.); +#331=EDGE_CURVE('',#279,#279,#243,.T.); +#332=EDGE_CURVE('',#279,#280,#151,.T.); +#333=EDGE_CURVE('',#280,#280,#244,.T.); +#334=EDGE_CURVE('',#281,#281,#245,.T.); +#335=EDGE_CURVE('',#281,#282,#152,.T.); +#336=EDGE_CURVE('',#282,#282,#246,.T.); +#337=EDGE_CURVE('',#283,#283,#247,.T.); +#338=EDGE_CURVE('',#283,#284,#153,.T.); +#339=EDGE_CURVE('',#284,#284,#248,.T.); +#340=EDGE_CURVE('',#285,#285,#249,.T.); +#341=EDGE_CURVE('',#285,#286,#154,.T.); +#342=EDGE_CURVE('',#286,#286,#250,.T.); +#343=EDGE_CURVE('',#287,#288,#251,.T.); +#344=EDGE_CURVE('',#287,#289,#155,.T.); +#345=EDGE_CURVE('',#290,#289,#252,.T.); +#346=EDGE_CURVE('',#288,#290,#156,.T.); +#347=EDGE_CURVE('',#291,#291,#253,.T.); +#348=EDGE_CURVE('',#291,#292,#157,.T.); +#349=EDGE_CURVE('',#292,#292,#254,.T.); +#350=EDGE_CURVE('',#293,#293,#255,.T.); +#351=EDGE_CURVE('',#293,#294,#158,.T.); +#352=EDGE_CURVE('',#294,#294,#256,.T.); +#353=EDGE_CURVE('',#295,#295,#257,.T.); +#354=EDGE_CURVE('',#295,#296,#159,.T.); +#355=EDGE_CURVE('',#296,#296,#258,.T.); +#356=EDGE_CURVE('',#297,#297,#259,.T.); +#357=EDGE_CURVE('',#297,#298,#160,.T.); +#358=EDGE_CURVE('',#298,#298,#260,.T.); +#359=EDGE_CURVE('',#299,#287,#161,.T.); +#360=EDGE_CURVE('',#299,#300,#162,.T.); +#361=EDGE_CURVE('',#300,#289,#163,.T.); +#362=EDGE_CURVE('',#301,#288,#164,.T.); +#363=EDGE_CURVE('',#301,#299,#165,.T.); +#364=EDGE_CURVE('',#302,#290,#166,.T.); +#365=EDGE_CURVE('',#301,#302,#167,.T.); +#366=EDGE_CURVE('',#302,#300,#168,.T.); +#367=EDGE_CURVE('',#303,#304,#261,.T.); +#368=EDGE_CURVE('',#303,#305,#169,.T.); +#369=EDGE_CURVE('',#305,#306,#170,.T.); +#370=EDGE_CURVE('',#304,#306,#171,.T.); +#371=EDGE_CURVE('',#307,#308,#262,.T.); +#372=EDGE_CURVE('',#308,#303,#172,.T.); +#373=EDGE_CURVE('',#304,#307,#173,.T.); +#374=EDGE_CURVE('',#309,#310,#263,.T.); +#375=EDGE_CURVE('',#310,#311,#174,.T.); +#376=EDGE_CURVE('',#311,#312,#264,.T.); +#377=EDGE_CURVE('',#312,#309,#175,.T.); +#378=EDGE_CURVE('',#312,#313,#176,.T.); +#379=EDGE_CURVE('',#314,#313,#177,.T.); +#380=EDGE_CURVE('',#309,#314,#178,.T.); +#381=EDGE_CURVE('',#307,#311,#179,.T.); +#382=EDGE_CURVE('',#308,#310,#180,.T.); +#383=EDGE_CURVE('',#300,#314,#265,.T.); +#384=EDGE_CURVE('',#313,#302,#266,.T.); +#385=EDGE_CURVE('',#315,#305,#267,.T.); +#386=EDGE_CURVE('',#316,#315,#181,.T.); +#387=EDGE_CURVE('',#306,#316,#268,.T.); +#388=EDGE_CURVE('',#315,#317,#182,.T.); +#389=EDGE_CURVE('',#317,#318,#183,.T.); +#390=EDGE_CURVE('',#316,#318,#184,.T.); +#391=EDGE_CURVE('',#299,#317,#269,.T.); +#392=EDGE_CURVE('',#318,#301,#270,.T.); +#393=EDGE_CURVE('',#305,#310,#185,.T.); +#394=EDGE_CURVE('',#315,#309,#186,.T.); +#395=EDGE_CURVE('',#316,#312,#187,.T.); +#396=EDGE_CURVE('',#306,#311,#188,.T.); +#397=EDGE_CURVE('',#318,#313,#189,.T.); +#398=EDGE_CURVE('',#317,#314,#190,.T.); +#399=ORIENTED_EDGE('',*,*,#319,.F.); +#400=ORIENTED_EDGE('',*,*,#320,.T.); +#401=ORIENTED_EDGE('',*,*,#321,.F.); +#402=ORIENTED_EDGE('',*,*,#320,.F.); +#403=ORIENTED_EDGE('',*,*,#322,.F.); +#404=ORIENTED_EDGE('',*,*,#323,.T.); +#405=ORIENTED_EDGE('',*,*,#324,.F.); +#406=ORIENTED_EDGE('',*,*,#323,.F.); +#407=ORIENTED_EDGE('',*,*,#325,.F.); +#408=ORIENTED_EDGE('',*,*,#326,.T.); +#409=ORIENTED_EDGE('',*,*,#327,.F.); +#410=ORIENTED_EDGE('',*,*,#326,.F.); +#411=ORIENTED_EDGE('',*,*,#328,.F.); +#412=ORIENTED_EDGE('',*,*,#329,.T.); +#413=ORIENTED_EDGE('',*,*,#330,.F.); +#414=ORIENTED_EDGE('',*,*,#329,.F.); +#415=ORIENTED_EDGE('',*,*,#331,.F.); +#416=ORIENTED_EDGE('',*,*,#332,.T.); +#417=ORIENTED_EDGE('',*,*,#333,.F.); +#418=ORIENTED_EDGE('',*,*,#332,.F.); +#419=ORIENTED_EDGE('',*,*,#334,.F.); +#420=ORIENTED_EDGE('',*,*,#335,.T.); +#421=ORIENTED_EDGE('',*,*,#336,.F.); +#422=ORIENTED_EDGE('',*,*,#335,.F.); +#423=ORIENTED_EDGE('',*,*,#337,.F.); +#424=ORIENTED_EDGE('',*,*,#338,.T.); +#425=ORIENTED_EDGE('',*,*,#339,.F.); +#426=ORIENTED_EDGE('',*,*,#338,.F.); +#427=ORIENTED_EDGE('',*,*,#340,.F.); +#428=ORIENTED_EDGE('',*,*,#341,.T.); +#429=ORIENTED_EDGE('',*,*,#342,.F.); +#430=ORIENTED_EDGE('',*,*,#341,.F.); +#431=ORIENTED_EDGE('',*,*,#343,.F.); +#432=ORIENTED_EDGE('',*,*,#344,.T.); +#433=ORIENTED_EDGE('',*,*,#345,.F.); +#434=ORIENTED_EDGE('',*,*,#346,.F.); +#435=ORIENTED_EDGE('',*,*,#347,.F.); +#436=ORIENTED_EDGE('',*,*,#348,.T.); +#437=ORIENTED_EDGE('',*,*,#349,.F.); +#438=ORIENTED_EDGE('',*,*,#348,.F.); +#439=ORIENTED_EDGE('',*,*,#350,.F.); +#440=ORIENTED_EDGE('',*,*,#351,.T.); +#441=ORIENTED_EDGE('',*,*,#352,.F.); +#442=ORIENTED_EDGE('',*,*,#351,.F.); +#443=ORIENTED_EDGE('',*,*,#353,.F.); +#444=ORIENTED_EDGE('',*,*,#354,.T.); +#445=ORIENTED_EDGE('',*,*,#355,.F.); +#446=ORIENTED_EDGE('',*,*,#354,.F.); +#447=ORIENTED_EDGE('',*,*,#356,.F.); +#448=ORIENTED_EDGE('',*,*,#357,.T.); +#449=ORIENTED_EDGE('',*,*,#358,.F.); +#450=ORIENTED_EDGE('',*,*,#357,.F.); +#451=ORIENTED_EDGE('',*,*,#344,.F.); +#452=ORIENTED_EDGE('',*,*,#359,.F.); +#453=ORIENTED_EDGE('',*,*,#360,.T.); +#454=ORIENTED_EDGE('',*,*,#361,.T.); +#455=ORIENTED_EDGE('',*,*,#343,.T.); +#456=ORIENTED_EDGE('',*,*,#362,.F.); +#457=ORIENTED_EDGE('',*,*,#363,.T.); +#458=ORIENTED_EDGE('',*,*,#359,.T.); +#459=ORIENTED_EDGE('',*,*,#355,.T.); +#460=ORIENTED_EDGE('',*,*,#352,.T.); +#461=ORIENTED_EDGE('',*,*,#349,.T.); +#462=ORIENTED_EDGE('',*,*,#342,.T.); +#463=ORIENTED_EDGE('',*,*,#339,.T.); +#464=ORIENTED_EDGE('',*,*,#336,.T.); +#465=ORIENTED_EDGE('',*,*,#333,.T.); +#466=ORIENTED_EDGE('',*,*,#346,.T.); +#467=ORIENTED_EDGE('',*,*,#364,.F.); +#468=ORIENTED_EDGE('',*,*,#365,.F.); +#469=ORIENTED_EDGE('',*,*,#362,.T.); +#470=ORIENTED_EDGE('',*,*,#345,.T.); +#471=ORIENTED_EDGE('',*,*,#361,.F.); +#472=ORIENTED_EDGE('',*,*,#366,.F.); +#473=ORIENTED_EDGE('',*,*,#364,.T.); +#474=ORIENTED_EDGE('',*,*,#331,.T.); +#475=ORIENTED_EDGE('',*,*,#334,.T.); +#476=ORIENTED_EDGE('',*,*,#337,.T.); +#477=ORIENTED_EDGE('',*,*,#340,.T.); +#478=ORIENTED_EDGE('',*,*,#347,.T.); +#479=ORIENTED_EDGE('',*,*,#350,.T.); +#480=ORIENTED_EDGE('',*,*,#353,.T.); +#481=ORIENTED_EDGE('',*,*,#367,.F.); +#482=ORIENTED_EDGE('',*,*,#368,.T.); +#483=ORIENTED_EDGE('',*,*,#369,.T.); +#484=ORIENTED_EDGE('',*,*,#370,.F.); +#485=ORIENTED_EDGE('',*,*,#321,.T.); +#486=ORIENTED_EDGE('',*,*,#324,.T.); +#487=ORIENTED_EDGE('',*,*,#327,.T.); +#488=ORIENTED_EDGE('',*,*,#330,.T.); +#489=ORIENTED_EDGE('',*,*,#358,.T.); +#490=ORIENTED_EDGE('',*,*,#371,.T.); +#491=ORIENTED_EDGE('',*,*,#372,.T.); +#492=ORIENTED_EDGE('',*,*,#367,.T.); +#493=ORIENTED_EDGE('',*,*,#373,.T.); +#494=ORIENTED_EDGE('',*,*,#374,.T.); +#495=ORIENTED_EDGE('',*,*,#375,.T.); +#496=ORIENTED_EDGE('',*,*,#376,.T.); +#497=ORIENTED_EDGE('',*,*,#377,.T.); +#498=ORIENTED_EDGE('',*,*,#377,.F.); +#499=ORIENTED_EDGE('',*,*,#378,.T.); +#500=ORIENTED_EDGE('',*,*,#379,.F.); +#501=ORIENTED_EDGE('',*,*,#380,.F.); +#502=ORIENTED_EDGE('',*,*,#371,.F.); +#503=ORIENTED_EDGE('',*,*,#381,.T.); +#504=ORIENTED_EDGE('',*,*,#375,.F.); +#505=ORIENTED_EDGE('',*,*,#382,.F.); +#506=ORIENTED_EDGE('',*,*,#319,.T.); +#507=ORIENTED_EDGE('',*,*,#322,.T.); +#508=ORIENTED_EDGE('',*,*,#325,.T.); +#509=ORIENTED_EDGE('',*,*,#328,.T.); +#510=ORIENTED_EDGE('',*,*,#356,.T.); +#511=ORIENTED_EDGE('',*,*,#383,.T.); +#512=ORIENTED_EDGE('',*,*,#379,.T.); +#513=ORIENTED_EDGE('',*,*,#384,.T.); +#514=ORIENTED_EDGE('',*,*,#366,.T.); +#515=ORIENTED_EDGE('',*,*,#385,.F.); +#516=ORIENTED_EDGE('',*,*,#386,.F.); +#517=ORIENTED_EDGE('',*,*,#387,.F.); +#518=ORIENTED_EDGE('',*,*,#369,.F.); +#519=ORIENTED_EDGE('',*,*,#386,.T.); +#520=ORIENTED_EDGE('',*,*,#388,.T.); +#521=ORIENTED_EDGE('',*,*,#389,.T.); +#522=ORIENTED_EDGE('',*,*,#390,.F.); +#523=ORIENTED_EDGE('',*,*,#391,.F.); +#524=ORIENTED_EDGE('',*,*,#363,.F.); +#525=ORIENTED_EDGE('',*,*,#392,.F.); +#526=ORIENTED_EDGE('',*,*,#389,.F.); +#527=ORIENTED_EDGE('',*,*,#385,.T.); +#528=ORIENTED_EDGE('',*,*,#393,.T.); +#529=ORIENTED_EDGE('',*,*,#374,.F.); +#530=ORIENTED_EDGE('',*,*,#394,.F.); +#531=ORIENTED_EDGE('',*,*,#387,.T.); +#532=ORIENTED_EDGE('',*,*,#395,.T.); +#533=ORIENTED_EDGE('',*,*,#376,.F.); +#534=ORIENTED_EDGE('',*,*,#396,.F.); +#535=ORIENTED_EDGE('',*,*,#390,.T.); +#536=ORIENTED_EDGE('',*,*,#397,.T.); +#537=ORIENTED_EDGE('',*,*,#378,.F.); +#538=ORIENTED_EDGE('',*,*,#395,.F.); +#539=ORIENTED_EDGE('',*,*,#388,.F.); +#540=ORIENTED_EDGE('',*,*,#394,.T.); +#541=ORIENTED_EDGE('',*,*,#380,.T.); +#542=ORIENTED_EDGE('',*,*,#398,.F.); +#543=ORIENTED_EDGE('',*,*,#372,.F.); +#544=ORIENTED_EDGE('',*,*,#382,.T.); +#545=ORIENTED_EDGE('',*,*,#393,.F.); +#546=ORIENTED_EDGE('',*,*,#368,.F.); +#547=ORIENTED_EDGE('',*,*,#373,.F.); +#548=ORIENTED_EDGE('',*,*,#370,.T.); +#549=ORIENTED_EDGE('',*,*,#396,.T.); +#550=ORIENTED_EDGE('',*,*,#381,.F.); +#551=ORIENTED_EDGE('',*,*,#391,.T.); +#552=ORIENTED_EDGE('',*,*,#398,.T.); +#553=ORIENTED_EDGE('',*,*,#383,.F.); +#554=ORIENTED_EDGE('',*,*,#360,.F.); +#555=ORIENTED_EDGE('',*,*,#392,.T.); +#556=ORIENTED_EDGE('',*,*,#365,.T.); +#557=ORIENTED_EDGE('',*,*,#384,.F.); +#558=ORIENTED_EDGE('',*,*,#397,.F.); +#559=CYLINDRICAL_SURFACE('',#625,1.6); +#560=CYLINDRICAL_SURFACE('',#628,1.6); +#561=CYLINDRICAL_SURFACE('',#631,1.6); +#562=CYLINDRICAL_SURFACE('',#634,1.6); +#563=CYLINDRICAL_SURFACE('',#637,1.6); +#564=CYLINDRICAL_SURFACE('',#640,1.6); +#565=CYLINDRICAL_SURFACE('',#643,1.6); +#566=CYLINDRICAL_SURFACE('',#646,7.00000000000001); +#567=CYLINDRICAL_SURFACE('',#649,17.5); +#568=CYLINDRICAL_SURFACE('',#652,1.6); +#569=CYLINDRICAL_SURFACE('',#655,1.6); +#570=CYLINDRICAL_SURFACE('',#658,1.6); +#571=CYLINDRICAL_SURFACE('',#661,7.); +#572=CYLINDRICAL_SURFACE('',#670,17.5); +#573=CYLINDRICAL_SURFACE('',#672,0.1); +#574=CYLINDRICAL_SURFACE('',#677,2.6); +#575=CYLINDRICAL_SURFACE('',#680,2.6); +#576=CYLINDRICAL_SURFACE('',#684,0.1); +#577=ADVANCED_FACE('',(#55),#559,.F.); +#578=ADVANCED_FACE('',(#56),#560,.F.); +#579=ADVANCED_FACE('',(#57),#561,.F.); +#580=ADVANCED_FACE('',(#58),#562,.F.); +#581=ADVANCED_FACE('',(#59),#563,.F.); +#582=ADVANCED_FACE('',(#60),#564,.F.); +#583=ADVANCED_FACE('',(#61),#565,.F.); +#584=ADVANCED_FACE('',(#62),#566,.F.); +#585=ADVANCED_FACE('',(#63),#567,.T.); +#586=ADVANCED_FACE('',(#64),#568,.F.); +#587=ADVANCED_FACE('',(#65),#569,.F.); +#588=ADVANCED_FACE('',(#66),#570,.F.); +#589=ADVANCED_FACE('',(#67),#571,.F.); +#590=ADVANCED_FACE('',(#68),#39,.F.); +#591=ADVANCED_FACE('',(#69,#15,#16,#17,#18,#19,#20,#21),#40,.F.); +#592=ADVANCED_FACE('',(#70),#41,.F.); +#593=ADVANCED_FACE('',(#71,#22,#23,#24,#25,#26,#27,#28),#42,.T.); +#594=ADVANCED_FACE('',(#72,#29,#30,#31,#32,#33),#43,.F.); +#595=ADVANCED_FACE('',(#73),#572,.T.); +#596=ADVANCED_FACE('',(#74),#573,.F.); +#597=ADVANCED_FACE('',(#75),#44,.T.); +#598=ADVANCED_FACE('',(#76,#34,#35,#36,#37,#38),#45,.T.); +#599=ADVANCED_FACE('',(#77),#574,.T.); +#600=ADVANCED_FACE('',(#78),#575,.T.); +#601=ADVANCED_FACE('',(#79),#46,.F.); +#602=ADVANCED_FACE('',(#80),#576,.F.); +#603=ADVANCED_FACE('',(#81),#47,.F.); +#604=ADVANCED_FACE('',(#82),#48,.F.); +#605=ADVANCED_FACE('',(#83),#49,.F.); +#606=ADVANCED_FACE('',(#84),#50,.F.); +#607=ADVANCED_FACE('',(#85),#51,.F.); +#608=ADVANCED_FACE('',(#86),#52,.F.); +#609=ADVANCED_FACE('',(#87),#53,.F.); +#610=ADVANCED_FACE('',(#88),#54,.F.); +#611=CLOSED_SHELL('',(#577,#578,#579,#580,#581,#582,#583,#584,#585,#586, +#587,#588,#589,#590,#591,#592,#593,#594,#595,#596,#597,#598,#599,#600,#601, +#602,#603,#604,#605,#606,#607,#608,#609,#610)); +#612=DERIVED_UNIT_ELEMENT(#614,1.); +#613=DERIVED_UNIT_ELEMENT(#1049,-3.); +#614=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT(.KILO.,.GRAM.) +); +#615=DERIVED_UNIT((#612,#613)); +#616=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(7850.),#615); +#617=PROPERTY_DEFINITION_REPRESENTATION(#622,#619); +#618=PROPERTY_DEFINITION_REPRESENTATION(#623,#620); +#619=REPRESENTATION('material name',(#621),#1046); +#620=REPRESENTATION('density',(#616),#1046); +#621=DESCRIPTIVE_REPRESENTATION_ITEM('Steel','Steel'); +#622=PROPERTY_DEFINITION('material property','material name',#1056); +#623=PROPERTY_DEFINITION('material property','density of part',#1056); +#624=AXIS2_PLACEMENT_3D('',#881,#695,#696); +#625=AXIS2_PLACEMENT_3D('',#882,#697,#698); +#626=AXIS2_PLACEMENT_3D('',#884,#699,#700); +#627=AXIS2_PLACEMENT_3D('',#887,#702,#703); +#628=AXIS2_PLACEMENT_3D('',#888,#704,#705); +#629=AXIS2_PLACEMENT_3D('',#890,#706,#707); +#630=AXIS2_PLACEMENT_3D('',#893,#709,#710); +#631=AXIS2_PLACEMENT_3D('',#894,#711,#712); +#632=AXIS2_PLACEMENT_3D('',#896,#713,#714); +#633=AXIS2_PLACEMENT_3D('',#899,#716,#717); +#634=AXIS2_PLACEMENT_3D('',#900,#718,#719); +#635=AXIS2_PLACEMENT_3D('',#902,#720,#721); +#636=AXIS2_PLACEMENT_3D('',#905,#723,#724); +#637=AXIS2_PLACEMENT_3D('',#906,#725,#726); +#638=AXIS2_PLACEMENT_3D('',#908,#727,#728); +#639=AXIS2_PLACEMENT_3D('',#911,#730,#731); +#640=AXIS2_PLACEMENT_3D('',#912,#732,#733); +#641=AXIS2_PLACEMENT_3D('',#914,#734,#735); +#642=AXIS2_PLACEMENT_3D('',#917,#737,#738); +#643=AXIS2_PLACEMENT_3D('',#918,#739,#740); +#644=AXIS2_PLACEMENT_3D('',#920,#741,#742); +#645=AXIS2_PLACEMENT_3D('',#923,#744,#745); +#646=AXIS2_PLACEMENT_3D('',#924,#746,#747); +#647=AXIS2_PLACEMENT_3D('',#926,#748,#749); +#648=AXIS2_PLACEMENT_3D('',#929,#751,#752); +#649=AXIS2_PLACEMENT_3D('',#930,#753,#754); +#650=AXIS2_PLACEMENT_3D('',#933,#755,#756); +#651=AXIS2_PLACEMENT_3D('',#937,#758,#759); +#652=AXIS2_PLACEMENT_3D('',#939,#761,#762); +#653=AXIS2_PLACEMENT_3D('',#941,#763,#764); +#654=AXIS2_PLACEMENT_3D('',#944,#766,#767); +#655=AXIS2_PLACEMENT_3D('',#945,#768,#769); +#656=AXIS2_PLACEMENT_3D('',#947,#770,#771); +#657=AXIS2_PLACEMENT_3D('',#950,#773,#774); +#658=AXIS2_PLACEMENT_3D('',#951,#775,#776); +#659=AXIS2_PLACEMENT_3D('',#953,#777,#778); +#660=AXIS2_PLACEMENT_3D('',#956,#780,#781); +#661=AXIS2_PLACEMENT_3D('',#957,#782,#783); +#662=AXIS2_PLACEMENT_3D('',#959,#784,#785); +#663=AXIS2_PLACEMENT_3D('',#962,#787,#788); +#664=AXIS2_PLACEMENT_3D('',#963,#789,#790); +#665=AXIS2_PLACEMENT_3D('',#969,#794,#795); +#666=AXIS2_PLACEMENT_3D('',#973,#798,#799); +#667=AXIS2_PLACEMENT_3D('',#977,#802,#803); +#668=AXIS2_PLACEMENT_3D('',#979,#805,#806); +#669=AXIS2_PLACEMENT_3D('',#982,#807,#808); +#670=AXIS2_PLACEMENT_3D('',#988,#812,#813); +#671=AXIS2_PLACEMENT_3D('',#991,#814,#815); +#672=AXIS2_PLACEMENT_3D('',#994,#818,#819); +#673=AXIS2_PLACEMENT_3D('',#997,#820,#821); +#674=AXIS2_PLACEMENT_3D('',#1001,#823,#824); +#675=AXIS2_PLACEMENT_3D('',#1003,#826,#827); +#676=AXIS2_PLACEMENT_3D('',#1009,#831,#832); +#677=AXIS2_PLACEMENT_3D('',#1012,#835,#836); +#678=AXIS2_PLACEMENT_3D('',#1013,#837,#838); +#679=AXIS2_PLACEMENT_3D('',#1014,#839,#840); +#680=AXIS2_PLACEMENT_3D('',#1015,#841,#842); +#681=AXIS2_PLACEMENT_3D('',#1017,#843,#844); +#682=AXIS2_PLACEMENT_3D('',#1020,#846,#847); +#683=AXIS2_PLACEMENT_3D('',#1021,#848,#849); +#684=AXIS2_PLACEMENT_3D('',#1027,#853,#854); +#685=AXIS2_PLACEMENT_3D('',#1028,#855,#856); +#686=AXIS2_PLACEMENT_3D('',#1029,#857,#858); +#687=AXIS2_PLACEMENT_3D('',#1030,#859,#860); +#688=AXIS2_PLACEMENT_3D('',#1033,#863,#864); +#689=AXIS2_PLACEMENT_3D('',#1036,#867,#868); +#690=AXIS2_PLACEMENT_3D('',#1038,#870,#871); +#691=AXIS2_PLACEMENT_3D('',#1040,#873,#874); +#692=AXIS2_PLACEMENT_3D('',#1041,#875,#876); +#693=AXIS2_PLACEMENT_3D('',#1042,#877,#878); +#694=AXIS2_PLACEMENT_3D('',#1043,#879,#880); +#695=DIRECTION('axis',(0.,0.,1.)); +#696=DIRECTION('refdir',(1.,0.,0.)); +#697=DIRECTION('center_axis',(-1.,0.,0.)); +#698=DIRECTION('ref_axis',(0.,1.,0.)); +#699=DIRECTION('center_axis',(-1.,0.,0.)); +#700=DIRECTION('ref_axis',(0.,1.,0.)); +#701=DIRECTION('',(-1.,0.,0.)); +#702=DIRECTION('center_axis',(1.,0.,0.)); +#703=DIRECTION('ref_axis',(0.,1.,0.)); +#704=DIRECTION('center_axis',(-1.,0.,0.)); +#705=DIRECTION('ref_axis',(0.,1.,0.)); +#706=DIRECTION('center_axis',(-1.,0.,0.)); +#707=DIRECTION('ref_axis',(0.,1.,0.)); +#708=DIRECTION('',(-1.,0.,0.)); +#709=DIRECTION('center_axis',(1.,0.,0.)); +#710=DIRECTION('ref_axis',(0.,1.,0.)); +#711=DIRECTION('center_axis',(-1.,0.,0.)); +#712=DIRECTION('ref_axis',(0.,1.,0.)); +#713=DIRECTION('center_axis',(-1.,0.,0.)); +#714=DIRECTION('ref_axis',(0.,1.,0.)); +#715=DIRECTION('',(-1.,0.,0.)); +#716=DIRECTION('center_axis',(1.,0.,0.)); +#717=DIRECTION('ref_axis',(0.,1.,0.)); +#718=DIRECTION('center_axis',(-1.,0.,0.)); +#719=DIRECTION('ref_axis',(0.,1.,0.)); +#720=DIRECTION('center_axis',(-1.,0.,0.)); +#721=DIRECTION('ref_axis',(0.,1.,0.)); +#722=DIRECTION('',(-1.,0.,0.)); +#723=DIRECTION('center_axis',(1.,0.,0.)); +#724=DIRECTION('ref_axis',(0.,1.,0.)); +#725=DIRECTION('center_axis',(-1.,0.,0.)); +#726=DIRECTION('ref_axis',(0.,0.,-1.)); +#727=DIRECTION('center_axis',(-1.,0.,0.)); +#728=DIRECTION('ref_axis',(0.,0.,-1.)); +#729=DIRECTION('',(-1.,0.,0.)); +#730=DIRECTION('center_axis',(1.,0.,0.)); +#731=DIRECTION('ref_axis',(0.,0.,-1.)); +#732=DIRECTION('center_axis',(-1.,0.,0.)); +#733=DIRECTION('ref_axis',(0.,0.,-1.)); +#734=DIRECTION('center_axis',(-1.,0.,0.)); +#735=DIRECTION('ref_axis',(0.,0.,-1.)); +#736=DIRECTION('',(-1.,0.,0.)); +#737=DIRECTION('center_axis',(1.,0.,0.)); +#738=DIRECTION('ref_axis',(0.,0.,-1.)); +#739=DIRECTION('center_axis',(-1.,0.,0.)); +#740=DIRECTION('ref_axis',(0.,0.,-1.)); +#741=DIRECTION('center_axis',(-1.,0.,0.)); +#742=DIRECTION('ref_axis',(0.,0.,-1.)); +#743=DIRECTION('',(-1.,0.,0.)); +#744=DIRECTION('center_axis',(1.,0.,0.)); +#745=DIRECTION('ref_axis',(0.,0.,-1.)); +#746=DIRECTION('center_axis',(-1.,0.,0.)); +#747=DIRECTION('ref_axis',(0.,0.,-1.)); +#748=DIRECTION('center_axis',(-1.,0.,0.)); +#749=DIRECTION('ref_axis',(0.,0.,-1.)); +#750=DIRECTION('',(-1.,0.,0.)); +#751=DIRECTION('center_axis',(1.,0.,0.)); +#752=DIRECTION('ref_axis',(0.,0.,-1.)); +#753=DIRECTION('center_axis',(-1.,0.,0.)); +#754=DIRECTION('ref_axis',(0.,0.,-1.)); +#755=DIRECTION('center_axis',(-1.,0.,0.)); +#756=DIRECTION('ref_axis',(0.,0.,-1.)); +#757=DIRECTION('',(1.,0.,0.)); +#758=DIRECTION('center_axis',(1.,0.,0.)); +#759=DIRECTION('ref_axis',(0.,0.,-1.)); +#760=DIRECTION('',(1.,0.,0.)); +#761=DIRECTION('center_axis',(-1.,0.,0.)); +#762=DIRECTION('ref_axis',(0.,0.,-1.)); +#763=DIRECTION('center_axis',(-1.,0.,0.)); +#764=DIRECTION('ref_axis',(0.,0.,-1.)); +#765=DIRECTION('',(-1.,0.,0.)); +#766=DIRECTION('center_axis',(1.,0.,0.)); +#767=DIRECTION('ref_axis',(0.,0.,-1.)); +#768=DIRECTION('center_axis',(-1.,0.,0.)); +#769=DIRECTION('ref_axis',(0.,0.,-1.)); +#770=DIRECTION('center_axis',(-1.,0.,0.)); +#771=DIRECTION('ref_axis',(0.,0.,-1.)); +#772=DIRECTION('',(-1.,0.,0.)); +#773=DIRECTION('center_axis',(1.,0.,0.)); +#774=DIRECTION('ref_axis',(0.,0.,-1.)); +#775=DIRECTION('center_axis',(-1.,0.,0.)); +#776=DIRECTION('ref_axis',(0.,0.,-1.)); +#777=DIRECTION('center_axis',(-1.,0.,0.)); +#778=DIRECTION('ref_axis',(0.,0.,-1.)); +#779=DIRECTION('',(-1.,0.,0.)); +#780=DIRECTION('center_axis',(1.,0.,0.)); +#781=DIRECTION('ref_axis',(0.,0.,-1.)); +#782=DIRECTION('center_axis',(-1.,0.,0.)); +#783=DIRECTION('ref_axis',(0.,0.,-1.)); +#784=DIRECTION('center_axis',(-1.,0.,0.)); +#785=DIRECTION('ref_axis',(0.,0.,-1.)); +#786=DIRECTION('',(-1.,0.,0.)); +#787=DIRECTION('center_axis',(1.,0.,0.)); +#788=DIRECTION('ref_axis',(0.,0.,-1.)); +#789=DIRECTION('center_axis',(0.,-1.,0.)); +#790=DIRECTION('ref_axis',(0.,0.,-1.)); +#791=DIRECTION('',(0.,0.,-1.)); +#792=DIRECTION('',(1.,0.,0.)); +#793=DIRECTION('',(0.,0.,-1.)); +#794=DIRECTION('center_axis',(1.,0.,0.)); +#795=DIRECTION('ref_axis',(0.,0.,-1.)); +#796=DIRECTION('',(0.,0.,-1.)); +#797=DIRECTION('',(0.,1.,0.)); +#798=DIRECTION('center_axis',(0.,1.,0.)); +#799=DIRECTION('ref_axis',(0.,0.,1.)); +#800=DIRECTION('',(0.,0.,-1.)); +#801=DIRECTION('',(1.,0.,0.)); +#802=DIRECTION('center_axis',(1.,0.,0.)); +#803=DIRECTION('ref_axis',(0.,0.,-1.)); +#804=DIRECTION('',(0.,1.,0.)); +#805=DIRECTION('center_axis',(1.,0.,0.)); +#806=DIRECTION('ref_axis',(0.,0.,-1.)); +#807=DIRECTION('center_axis',(1.,0.,0.)); +#808=DIRECTION('ref_axis',(0.,0.707106781186548,0.707106781186548)); +#809=DIRECTION('',(0.,0.,-1.)); +#810=DIRECTION('',(0.,-1.,0.)); +#811=DIRECTION('',(2.73910036535074E-33,0.,-1.)); +#812=DIRECTION('center_axis',(1.,0.,0.)); +#813=DIRECTION('ref_axis',(0.,0.707106781186548,0.707106781186548)); +#814=DIRECTION('center_axis',(-1.,0.,0.)); +#815=DIRECTION('ref_axis',(0.,0.707106781186548,0.707106781186548)); +#816=DIRECTION('',(-1.,0.,0.)); +#817=DIRECTION('',(1.,0.,0.)); +#818=DIRECTION('center_axis',(0.,1.,0.)); +#819=DIRECTION('ref_axis',(-0.923879532511287,0.,-0.382683432365088)); +#820=DIRECTION('center_axis',(0.,1.,0.)); +#821=DIRECTION('ref_axis',(-0.923879532511287,0.,-0.382683432365089)); +#822=DIRECTION('',(0.,-1.,0.)); +#823=DIRECTION('center_axis',(0.,-1.,0.)); +#824=DIRECTION('ref_axis',(-0.923879532511287,0.,-0.382683432365089)); +#825=DIRECTION('',(0.,1.,0.)); +#826=DIRECTION('center_axis',(0.707106781186549,0.,0.707106781186546)); +#827=DIRECTION('ref_axis',(0.707106781186546,0.,-0.707106781186549)); +#828=DIRECTION('',(0.707106781186546,0.,-0.707106781186549)); +#829=DIRECTION('',(0.,-1.,0.)); +#830=DIRECTION('',(0.707106781186546,0.,-0.707106781186549)); +#831=DIRECTION('center_axis',(1.,0.,0.)); +#832=DIRECTION('ref_axis',(0.,0.,-1.)); +#833=DIRECTION('',(2.73910036535074E-33,0.,-1.)); +#834=DIRECTION('',(0.,0.,-1.)); +#835=DIRECTION('center_axis',(0.,1.,0.)); +#836=DIRECTION('ref_axis',(0.92387953251127,0.,0.38268343236513)); +#837=DIRECTION('center_axis',(0.,-1.,0.)); +#838=DIRECTION('ref_axis',(0.923879532511279,0.,0.382683432365109)); +#839=DIRECTION('center_axis',(0.,1.,0.)); +#840=DIRECTION('ref_axis',(0.923879532511279,0.,0.382683432365109)); +#841=DIRECTION('center_axis',(0.,1.,0.)); +#842=DIRECTION('ref_axis',(-0.923879532511287,0.,-0.382683432365088)); +#843=DIRECTION('center_axis',(0.,1.,0.)); +#844=DIRECTION('ref_axis',(-0.923879532511287,0.,-0.382683432365089)); +#845=DIRECTION('',(0.,1.,0.)); +#846=DIRECTION('center_axis',(0.,-1.,0.)); +#847=DIRECTION('ref_axis',(-0.923879532511287,0.,-0.382683432365089)); +#848=DIRECTION('center_axis',(0.707106781186549,0.,0.707106781186546)); +#849=DIRECTION('ref_axis',(0.707106781186546,0.,-0.707106781186549)); +#850=DIRECTION('',(0.707106781186546,0.,-0.707106781186549)); +#851=DIRECTION('',(0.,-1.,0.)); +#852=DIRECTION('',(0.707106781186546,0.,-0.707106781186549)); +#853=DIRECTION('center_axis',(0.,1.,0.)); +#854=DIRECTION('ref_axis',(0.92387953251127,0.,0.38268343236513)); +#855=DIRECTION('center_axis',(0.,-1.,0.)); +#856=DIRECTION('ref_axis',(0.923879532511279,0.,0.382683432365109)); +#857=DIRECTION('center_axis',(0.,1.,0.)); +#858=DIRECTION('ref_axis',(0.923879532511279,0.,0.382683432365109)); +#859=DIRECTION('center_axis',(0.,-1.,0.)); +#860=DIRECTION('ref_axis',(0.,0.,-1.)); +#861=DIRECTION('',(1.,0.,0.)); +#862=DIRECTION('',(0.70710678118655,0.,0.707106781186546)); +#863=DIRECTION('center_axis',(0.,1.,0.)); +#864=DIRECTION('ref_axis',(0.,0.,1.)); +#865=DIRECTION('',(0.70710678118655,0.,0.707106781186546)); +#866=DIRECTION('',(1.,0.,0.)); +#867=DIRECTION('center_axis',(0.,1.,0.)); +#868=DIRECTION('ref_axis',(0.,0.,1.)); +#869=DIRECTION('',(0.707106781186548,0.,0.707106781186547)); +#870=DIRECTION('center_axis',(0.,-1.,0.)); +#871=DIRECTION('ref_axis',(0.,0.,-1.)); +#872=DIRECTION('',(0.707106781186548,0.,0.707106781186547)); +#873=DIRECTION('center_axis',(0.,-1.,0.)); +#874=DIRECTION('ref_axis',(0.,0.,-1.)); +#875=DIRECTION('center_axis',(0.,1.,0.)); +#876=DIRECTION('ref_axis',(0.,0.,1.)); +#877=DIRECTION('center_axis',(0.,-1.,0.)); +#878=DIRECTION('ref_axis',(0.,0.,-1.)); +#879=DIRECTION('center_axis',(0.,1.,0.)); +#880=DIRECTION('ref_axis',(0.,0.,1.)); +#881=CARTESIAN_POINT('',(0.,0.,0.)); +#882=CARTESIAN_POINT('Origin',(-16.75,7.95405845398161,9.54594154601839)); +#883=CARTESIAN_POINT('',(2.5,6.35405845398161,9.54594154601839)); +#884=CARTESIAN_POINT('Origin',(2.5,7.95405845398161,9.54594154601839)); +#885=CARTESIAN_POINT('',(0.,6.35405845398161,9.54594154601839)); +#886=CARTESIAN_POINT('',(-16.75,6.35405845398161,9.54594154601839)); +#887=CARTESIAN_POINT('Origin',(0.,7.95405845398161,9.54594154601839)); +#888=CARTESIAN_POINT('Origin',(-16.75,27.0459415460184,-9.54594154601839)); +#889=CARTESIAN_POINT('',(2.5,25.4459415460184,-9.54594154601839)); +#890=CARTESIAN_POINT('Origin',(2.5,27.0459415460184,-9.54594154601839)); +#891=CARTESIAN_POINT('',(0.,25.4459415460184,-9.54594154601839)); +#892=CARTESIAN_POINT('',(-16.75,25.4459415460184,-9.54594154601839)); +#893=CARTESIAN_POINT('Origin',(0.,27.0459415460184,-9.54594154601839)); +#894=CARTESIAN_POINT('Origin',(-16.75,27.0459415460184,9.54594154601839)); +#895=CARTESIAN_POINT('',(2.5,25.4459415460184,9.54594154601839)); +#896=CARTESIAN_POINT('Origin',(2.5,27.0459415460184,9.54594154601839)); +#897=CARTESIAN_POINT('',(0.,25.4459415460184,9.54594154601839)); +#898=CARTESIAN_POINT('',(-16.75,25.4459415460184,9.54594154601839)); +#899=CARTESIAN_POINT('Origin',(0.,27.0459415460184,9.54594154601839)); +#900=CARTESIAN_POINT('Origin',(-16.75,7.95405845398161,-9.54594154601839)); +#901=CARTESIAN_POINT('',(2.5,6.35405845398161,-9.54594154601839)); +#902=CARTESIAN_POINT('Origin',(2.5,7.95405845398161,-9.54594154601839)); +#903=CARTESIAN_POINT('',(0.,6.35405845398161,-9.54594154601839)); +#904=CARTESIAN_POINT('',(-16.75,6.35405845398161,-9.54594154601839)); +#905=CARTESIAN_POINT('Origin',(0.,7.95405845398161,-9.54594154601839)); +#906=CARTESIAN_POINT('Origin',(21.75,31.,-84.853)); +#907=CARTESIAN_POINT('',(21.75,31.,-83.253)); +#908=CARTESIAN_POINT('Origin',(21.75,31.,-84.853)); +#909=CARTESIAN_POINT('',(19.25,31.,-83.253)); +#910=CARTESIAN_POINT('',(21.75,31.,-83.253)); +#911=CARTESIAN_POINT('Origin',(19.25,31.,-84.853)); +#912=CARTESIAN_POINT('Origin',(21.75,10.75,-73.1616570489101)); +#913=CARTESIAN_POINT('',(21.75,10.75,-71.5616570489101)); +#914=CARTESIAN_POINT('Origin',(21.75,10.75,-73.1616570489101)); +#915=CARTESIAN_POINT('',(19.25,10.75,-71.5616570489101)); +#916=CARTESIAN_POINT('',(21.75,10.75,-71.5616570489101)); +#917=CARTESIAN_POINT('Origin',(19.25,10.75,-73.1616570489101)); +#918=CARTESIAN_POINT('Origin',(21.75,4.00000000000002,-84.853)); +#919=CARTESIAN_POINT('',(21.75,4.00000000000002,-83.253)); +#920=CARTESIAN_POINT('Origin',(21.75,4.00000000000002,-84.853)); +#921=CARTESIAN_POINT('',(19.25,4.00000000000002,-83.253)); +#922=CARTESIAN_POINT('',(21.75,4.00000000000002,-83.253)); +#923=CARTESIAN_POINT('Origin',(19.25,4.00000000000002,-84.853)); +#924=CARTESIAN_POINT('Origin',(21.75,17.5,-84.853)); +#925=CARTESIAN_POINT('',(21.75,17.5,-77.853)); +#926=CARTESIAN_POINT('Origin',(21.75,17.5,-84.853)); +#927=CARTESIAN_POINT('',(19.25,17.5,-77.853)); +#928=CARTESIAN_POINT('',(21.75,17.5,-77.853)); +#929=CARTESIAN_POINT('Origin',(19.25,17.5,-84.853)); +#930=CARTESIAN_POINT('Origin',(21.75,17.5,-84.853)); +#931=CARTESIAN_POINT('',(19.25,35.,-84.853)); +#932=CARTESIAN_POINT('',(19.25,0.,-84.853)); +#933=CARTESIAN_POINT('Origin',(19.25,17.5,-84.853)); +#934=CARTESIAN_POINT('',(21.75,35.,-84.853)); +#935=CARTESIAN_POINT('',(21.75,35.,-84.853)); +#936=CARTESIAN_POINT('',(21.75,0.,-84.853)); +#937=CARTESIAN_POINT('Origin',(21.75,17.5,-84.853)); +#938=CARTESIAN_POINT('',(21.75,0.,-84.853)); +#939=CARTESIAN_POINT('Origin',(21.75,24.25,-96.5443429510899)); +#940=CARTESIAN_POINT('',(21.75,24.25,-94.9443429510899)); +#941=CARTESIAN_POINT('Origin',(21.75,24.25,-96.5443429510899)); +#942=CARTESIAN_POINT('',(19.25,24.25,-94.9443429510899)); +#943=CARTESIAN_POINT('',(21.75,24.25,-94.9443429510899)); +#944=CARTESIAN_POINT('Origin',(19.25,24.25,-96.5443429510899)); +#945=CARTESIAN_POINT('Origin',(21.75,24.25,-73.1616570489101)); +#946=CARTESIAN_POINT('',(21.75,24.25,-71.5616570489101)); +#947=CARTESIAN_POINT('Origin',(21.75,24.25,-73.1616570489101)); +#948=CARTESIAN_POINT('',(19.25,24.25,-71.5616570489101)); +#949=CARTESIAN_POINT('',(21.75,24.25,-71.5616570489101)); +#950=CARTESIAN_POINT('Origin',(19.25,24.25,-73.1616570489101)); +#951=CARTESIAN_POINT('Origin',(21.75,10.75,-96.5443429510899)); +#952=CARTESIAN_POINT('',(21.75,10.75,-94.9443429510899)); +#953=CARTESIAN_POINT('Origin',(21.75,10.75,-96.5443429510899)); +#954=CARTESIAN_POINT('',(19.25,10.75,-94.9443429510899)); +#955=CARTESIAN_POINT('',(21.75,10.75,-94.9443429510899)); +#956=CARTESIAN_POINT('Origin',(19.25,10.75,-96.5443429510899)); +#957=CARTESIAN_POINT('Origin',(21.75,17.5,0.)); +#958=CARTESIAN_POINT('',(2.5,17.5,7.)); +#959=CARTESIAN_POINT('Origin',(2.5,17.5,0.)); +#960=CARTESIAN_POINT('',(0.,17.5,7.)); +#961=CARTESIAN_POINT('',(21.75,17.5,7.)); +#962=CARTESIAN_POINT('Origin',(0.,17.5,0.)); +#963=CARTESIAN_POINT('Origin',(19.25,35.,-72.0722106781187)); +#964=CARTESIAN_POINT('',(19.25,35.,-41.7914213562374)); +#965=CARTESIAN_POINT('',(19.25,35.,-67.353)); +#966=CARTESIAN_POINT('',(21.75,35.,-41.7914213562374)); +#967=CARTESIAN_POINT('',(19.25,35.,-41.7914213562374)); +#968=CARTESIAN_POINT('',(21.75,35.,-67.353)); +#969=CARTESIAN_POINT('Origin',(19.25,0.,-41.7500000000001)); +#970=CARTESIAN_POINT('',(19.25,0.,-41.7914213562374)); +#971=CARTESIAN_POINT('',(19.25,0.,-67.353)); +#972=CARTESIAN_POINT('',(19.25,0.,-41.7914213562374)); +#973=CARTESIAN_POINT('Origin',(19.25,0.,-72.0722106781187)); +#974=CARTESIAN_POINT('',(21.75,0.,-41.7914213562374)); +#975=CARTESIAN_POINT('',(21.75,0.,-67.353)); +#976=CARTESIAN_POINT('',(19.25,0.,-41.7914213562374)); +#977=CARTESIAN_POINT('Origin',(21.75,0.,-41.7500000000001)); +#978=CARTESIAN_POINT('',(21.75,0.,-41.7914213562374)); +#979=CARTESIAN_POINT('Origin',(0.,0.,17.5)); +#980=CARTESIAN_POINT('',(0.,35.,0.)); +#981=CARTESIAN_POINT('',(0.,0.,0.)); +#982=CARTESIAN_POINT('Origin',(0.,17.5,0.)); +#983=CARTESIAN_POINT('',(0.,35.,-21.42304473783)); +#984=CARTESIAN_POINT('',(0.,35.,0.)); +#985=CARTESIAN_POINT('',(5.86798696683152E-32,0.,-21.42304473783)); +#986=CARTESIAN_POINT('',(0.,0.,-21.42304473783)); +#987=CARTESIAN_POINT('',(0.,0.,0.)); +#988=CARTESIAN_POINT('Origin',(0.,17.5,0.)); +#989=CARTESIAN_POINT('',(2.5,0.,0.)); +#990=CARTESIAN_POINT('',(2.5,35.,0.)); +#991=CARTESIAN_POINT('Origin',(2.5,17.5,0.)); +#992=CARTESIAN_POINT('',(0.,35.,0.)); +#993=CARTESIAN_POINT('',(2.68640331866933E-33,0.,0.)); +#994=CARTESIAN_POINT('Origin',(2.6,0.,-21.42304473783)); +#995=CARTESIAN_POINT('',(2.52928932188135,35.,-21.4937554159486)); +#996=CARTESIAN_POINT('',(2.5,35.,-21.42304473783)); +#997=CARTESIAN_POINT('Origin',(2.6,35.,-21.42304473783)); +#998=CARTESIAN_POINT('',(2.5,0.,-21.42304473783)); +#999=CARTESIAN_POINT('',(2.5,0.,-21.42304473783)); +#1000=CARTESIAN_POINT('',(2.52928932188135,0.,-21.4937554159486)); +#1001=CARTESIAN_POINT('Origin',(2.6,0.,-21.42304473783)); +#1002=CARTESIAN_POINT('',(2.52928932188135,0.,-21.4937554159486)); +#1003=CARTESIAN_POINT('Origin',(1.76776695296637,0.,-20.7322330470336)); +#1004=CARTESIAN_POINT('',(20.988477631085,0.,-39.9529437251524)); +#1005=CARTESIAN_POINT('',(1.76776695296637,0.,-20.7322330470336)); +#1006=CARTESIAN_POINT('',(20.988477631085,35.,-39.9529437251524)); +#1007=CARTESIAN_POINT('',(20.988477631085,0.,-39.9529437251524)); +#1008=CARTESIAN_POINT('',(1.76776695296637,35.,-20.7322330470336)); +#1009=CARTESIAN_POINT('Origin',(2.5,0.,17.5)); +#1010=CARTESIAN_POINT('',(2.5,0.,0.)); +#1011=CARTESIAN_POINT('',(2.5,35.,0.)); +#1012=CARTESIAN_POINT('Origin',(19.15,0.,-41.7914213562374)); +#1013=CARTESIAN_POINT('Origin',(19.15,35.,-41.7914213562374)); +#1014=CARTESIAN_POINT('Origin',(19.15,0.,-41.7914213562374)); +#1015=CARTESIAN_POINT('Origin',(2.6,0.,-21.42304473783)); +#1016=CARTESIAN_POINT('',(0.761522368914971,35.,-23.261522368915)); +#1017=CARTESIAN_POINT('Origin',(2.6,35.,-21.42304473783)); +#1018=CARTESIAN_POINT('',(0.761522368914971,0.,-23.261522368915)); +#1019=CARTESIAN_POINT('',(0.761522368914971,0.,-23.261522368915)); +#1020=CARTESIAN_POINT('Origin',(2.6,0.,-21.42304473783)); +#1021=CARTESIAN_POINT('Origin',(6.16297582203915E-32,0.,-22.5)); +#1022=CARTESIAN_POINT('',(19.2207106781187,35.,-41.7207106781188)); +#1023=CARTESIAN_POINT('',(6.16297582203915E-32,35.,-22.5)); +#1024=CARTESIAN_POINT('',(19.2207106781187,0.,-41.7207106781188)); +#1025=CARTESIAN_POINT('',(19.2207106781187,0.,-41.7207106781188)); +#1026=CARTESIAN_POINT('',(6.16297582203915E-32,0.,-22.5)); +#1027=CARTESIAN_POINT('Origin',(19.15,0.,-41.7914213562374)); +#1028=CARTESIAN_POINT('Origin',(19.15,35.,-41.7914213562374)); +#1029=CARTESIAN_POINT('Origin',(19.15,0.,-41.7914213562374)); +#1030=CARTESIAN_POINT('Origin',(0.197913215470653,35.,-22.4180216619792)); +#1031=CARTESIAN_POINT('',(0.,35.,-21.42304473783)); +#1032=CARTESIAN_POINT('',(0.761522368914971,35.,-23.261522368915)); +#1033=CARTESIAN_POINT('Origin',(0.197913215470653,0.,-22.4180216619792)); +#1034=CARTESIAN_POINT('',(0.761522368914971,0.,-23.261522368915)); +#1035=CARTESIAN_POINT('',(5.86798696683152E-32,0.,-21.42304473783)); +#1036=CARTESIAN_POINT('Origin',(9.99111652351681,0.,-32.4911165235169)); +#1037=CARTESIAN_POINT('',(19.2207106781187,0.,-41.7207106781188)); +#1038=CARTESIAN_POINT('Origin',(9.99111652351681,35.,-32.4911165235169)); +#1039=CARTESIAN_POINT('',(19.2207106781187,35.,-41.7207106781188)); +#1040=CARTESIAN_POINT('Origin',(0.,35.,-1.96152236891498)); +#1041=CARTESIAN_POINT('Origin',(5.37280663733866E-33,0.,-1.96152236891498)); +#1042=CARTESIAN_POINT('Origin',(19.2423879532511,35.,-41.7531530130009)); +#1043=CARTESIAN_POINT('Origin',(19.2423879532511,0.,-41.7531530130009)); +#1044=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1048, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1045=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1048, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1046=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1044)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1048,#1050,#1051)) +REPRESENTATION_CONTEXT('','3D') +); +#1047=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1045)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1048,#1050,#1051)) +REPRESENTATION_CONTEXT('','3D') +); +#1048=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#1049=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT($,.METRE.) +); +#1050=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#1051=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#1052=SHAPE_DEFINITION_REPRESENTATION(#1053,#1054); +#1053=PRODUCT_DEFINITION_SHAPE('',$,#1056); +#1054=SHAPE_REPRESENTATION('',(#624),#1046); +#1055=PRODUCT_DEFINITION_CONTEXT('part definition',#1060,'design'); +#1056=PRODUCT_DEFINITION('link3-4-1','link3-4-1 v2',#1057,#1055); +#1057=PRODUCT_DEFINITION_FORMATION('',$,#1062); +#1058=PRODUCT_RELATED_PRODUCT_CATEGORY('link3-4-1 v2','link3-4-1 v2',(#1062)); +#1059=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#1060); +#1060=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#1061=PRODUCT_CONTEXT('part definition',#1060,'mechanical'); +#1062=PRODUCT('link3-4-1','link3-4-1 v2',$,(#1061)); +#1063=PRESENTATION_STYLE_ASSIGNMENT((#1065)); +#1064=PRESENTATION_STYLE_ASSIGNMENT((#1066)); +#1065=SURFACE_STYLE_USAGE(.BOTH.,#1067); +#1066=SURFACE_STYLE_USAGE(.BOTH.,#1068); +#1067=SURFACE_SIDE_STYLE('',(#1069)); +#1068=SURFACE_SIDE_STYLE('',(#1070)); +#1069=SURFACE_STYLE_FILL_AREA(#1071); +#1070=SURFACE_STYLE_FILL_AREA(#1072); +#1071=FILL_AREA_STYLE('Steel - Satin',(#1073)); +#1072=FILL_AREA_STYLE('Aluminum - Satin',(#1074)); +#1073=FILL_AREA_STYLE_COLOUR('Steel - Satin',#1075); +#1074=FILL_AREA_STYLE_COLOUR('Aluminum - Satin',#1076); +#1075=COLOUR_RGB('Steel - Satin',0.627450980392157,0.627450980392157,0.627450980392157); +#1076=COLOUR_RGB('Aluminum - Satin',0.96078431372549,0.96078431372549,0.964705882352941); +ENDSEC; +END-ISO-10303-21; diff --git a/hardware/follower_STEPs/link3-4-2_v0.2.0.step b/hardware/follower_STEPs/link3-4-2_v0.2.0.step new file mode 100644 index 0000000000000000000000000000000000000000..92f0371730438b8554c1177181c1270f4bff718c --- /dev/null +++ b/hardware/follower_STEPs/link3-4-2_v0.2.0.step @@ -0,0 +1,1344 @@ +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 */ 'link3-4-2_v0.2.0.step', +/* time_stamp */ '2025-10-08T20:56:34+02:00', +/* author */ (''), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v20.1', +/* originating_system */ 'Autodesk Translation Framework v14.17.0.0', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#1253); +#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#1260,#12); +#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#1252); +#13=STYLED_ITEM('',(#1270),#14); +#14=MANIFOLD_SOLID_BREP('Body1',#725); +#15=FACE_BOUND('',#128,.T.); +#16=FACE_BOUND('',#129,.T.); +#17=FACE_BOUND('',#130,.T.); +#18=FACE_BOUND('',#131,.T.); +#19=FACE_BOUND('',#132,.T.); +#20=FACE_BOUND('',#133,.T.); +#21=FACE_BOUND('',#134,.T.); +#22=FACE_BOUND('',#135,.T.); +#23=FACE_BOUND('',#136,.T.); +#24=FACE_BOUND('',#137,.T.); +#25=FACE_BOUND('',#138,.T.); +#26=FACE_BOUND('',#140,.T.); +#27=FACE_BOUND('',#141,.T.); +#28=FACE_BOUND('',#142,.T.); +#29=FACE_BOUND('',#143,.T.); +#30=FACE_BOUND('',#144,.T.); +#31=FACE_BOUND('',#145,.T.); +#32=FACE_BOUND('',#146,.T.); +#33=FACE_BOUND('',#147,.T.); +#34=FACE_BOUND('',#148,.T.); +#35=FACE_BOUND('',#149,.T.); +#36=FACE_BOUND('',#150,.T.); +#37=FACE_BOUND('',#155,.T.); +#38=FACE_BOUND('',#156,.T.); +#39=FACE_BOUND('',#157,.T.); +#40=FACE_BOUND('',#158,.T.); +#41=FACE_BOUND('',#159,.T.); +#42=FACE_BOUND('',#164,.T.); +#43=FACE_BOUND('',#165,.T.); +#44=FACE_BOUND('',#166,.T.); +#45=FACE_BOUND('',#167,.T.); +#46=FACE_BOUND('',#168,.T.); +#47=ELLIPSE('',#795,0.102197588636764,0.100000000000001); +#48=ELLIPSE('',#796,2.65713730455585,2.6); +#49=ELLIPSE('',#797,0.102197588636764,0.1); +#50=ELLIPSE('',#798,2.65713730455585,2.6); +#51=ELLIPSE('',#803,2.65713730455586,2.6); +#52=ELLIPSE('',#804,0.102197588636764,0.1); +#53=ELLIPSE('',#805,2.65713730455585,2.6); +#54=ELLIPSE('',#806,0.102197588636764,0.100000000000001); +#55=PLANE('',#793); +#56=PLANE('',#794); +#57=PLANE('',#802); +#58=PLANE('',#807); +#59=PLANE('',#817); +#60=PLANE('',#818); +#61=PLANE('',#820); +#62=PLANE('',#822); +#63=PLANE('',#824); +#64=PLANE('',#826); +#65=FACE_OUTER_BOUND('',#101,.T.); +#66=FACE_OUTER_BOUND('',#102,.T.); +#67=FACE_OUTER_BOUND('',#103,.T.); +#68=FACE_OUTER_BOUND('',#104,.T.); +#69=FACE_OUTER_BOUND('',#105,.T.); +#70=FACE_OUTER_BOUND('',#106,.T.); +#71=FACE_OUTER_BOUND('',#107,.T.); +#72=FACE_OUTER_BOUND('',#108,.T.); +#73=FACE_OUTER_BOUND('',#109,.T.); +#74=FACE_OUTER_BOUND('',#110,.T.); +#75=FACE_OUTER_BOUND('',#111,.T.); +#76=FACE_OUTER_BOUND('',#112,.T.); +#77=FACE_OUTER_BOUND('',#113,.T.); +#78=FACE_OUTER_BOUND('',#114,.T.); +#79=FACE_OUTER_BOUND('',#115,.T.); +#80=FACE_OUTER_BOUND('',#116,.T.); +#81=FACE_OUTER_BOUND('',#117,.T.); +#82=FACE_OUTER_BOUND('',#118,.T.); +#83=FACE_OUTER_BOUND('',#119,.T.); +#84=FACE_OUTER_BOUND('',#120,.T.); +#85=FACE_OUTER_BOUND('',#121,.T.); +#86=FACE_OUTER_BOUND('',#122,.T.); +#87=FACE_OUTER_BOUND('',#123,.T.); +#88=FACE_OUTER_BOUND('',#124,.T.); +#89=FACE_OUTER_BOUND('',#125,.T.); +#90=FACE_OUTER_BOUND('',#126,.T.); +#91=FACE_OUTER_BOUND('',#127,.T.); +#92=FACE_OUTER_BOUND('',#139,.T.); +#93=FACE_OUTER_BOUND('',#151,.T.); +#94=FACE_OUTER_BOUND('',#152,.T.); +#95=FACE_OUTER_BOUND('',#153,.T.); +#96=FACE_OUTER_BOUND('',#154,.T.); +#97=FACE_OUTER_BOUND('',#160,.T.); +#98=FACE_OUTER_BOUND('',#161,.T.); +#99=FACE_OUTER_BOUND('',#162,.T.); +#100=FACE_OUTER_BOUND('',#163,.T.); +#101=EDGE_LOOP('',(#467,#468,#469,#470)); +#102=EDGE_LOOP('',(#471,#472,#473,#474)); +#103=EDGE_LOOP('',(#475,#476,#477,#478)); +#104=EDGE_LOOP('',(#479,#480,#481,#482)); +#105=EDGE_LOOP('',(#483,#484,#485,#486)); +#106=EDGE_LOOP('',(#487,#488,#489,#490)); +#107=EDGE_LOOP('',(#491,#492,#493,#494)); +#108=EDGE_LOOP('',(#495,#496,#497,#498)); +#109=EDGE_LOOP('',(#499,#500,#501,#502)); +#110=EDGE_LOOP('',(#503,#504,#505,#506)); +#111=EDGE_LOOP('',(#507,#508,#509,#510)); +#112=EDGE_LOOP('',(#511,#512,#513,#514)); +#113=EDGE_LOOP('',(#515,#516,#517,#518)); +#114=EDGE_LOOP('',(#519,#520,#521,#522)); +#115=EDGE_LOOP('',(#523,#524,#525,#526)); +#116=EDGE_LOOP('',(#527,#528,#529,#530)); +#117=EDGE_LOOP('',(#531,#532,#533,#534)); +#118=EDGE_LOOP('',(#535,#536,#537,#538)); +#119=EDGE_LOOP('',(#539,#540,#541,#542)); +#120=EDGE_LOOP('',(#543,#544,#545,#546,#547,#548,#549,#550,#551,#552)); +#121=EDGE_LOOP('',(#553,#554,#555,#556)); +#122=EDGE_LOOP('',(#557,#558,#559,#560,#561,#562,#563,#564,#565,#566)); +#123=EDGE_LOOP('',(#567,#568,#569,#570)); +#124=EDGE_LOOP('',(#571,#572,#573,#574)); +#125=EDGE_LOOP('',(#575,#576,#577,#578)); +#126=EDGE_LOOP('',(#579,#580,#581,#582)); +#127=EDGE_LOOP('',(#583,#584,#585,#586)); +#128=EDGE_LOOP('',(#587)); +#129=EDGE_LOOP('',(#588)); +#130=EDGE_LOOP('',(#589)); +#131=EDGE_LOOP('',(#590)); +#132=EDGE_LOOP('',(#591)); +#133=EDGE_LOOP('',(#592)); +#134=EDGE_LOOP('',(#593)); +#135=EDGE_LOOP('',(#594)); +#136=EDGE_LOOP('',(#595)); +#137=EDGE_LOOP('',(#596)); +#138=EDGE_LOOP('',(#597)); +#139=EDGE_LOOP('',(#598,#599,#600,#601)); +#140=EDGE_LOOP('',(#602)); +#141=EDGE_LOOP('',(#603)); +#142=EDGE_LOOP('',(#604)); +#143=EDGE_LOOP('',(#605)); +#144=EDGE_LOOP('',(#606)); +#145=EDGE_LOOP('',(#607)); +#146=EDGE_LOOP('',(#608)); +#147=EDGE_LOOP('',(#609)); +#148=EDGE_LOOP('',(#610)); +#149=EDGE_LOOP('',(#611)); +#150=EDGE_LOOP('',(#612)); +#151=EDGE_LOOP('',(#613,#614,#615,#616)); +#152=EDGE_LOOP('',(#617,#618,#619,#620)); +#153=EDGE_LOOP('',(#621,#622,#623,#624)); +#154=EDGE_LOOP('',(#625,#626,#627,#628,#629,#630,#631,#632)); +#155=EDGE_LOOP('',(#633)); +#156=EDGE_LOOP('',(#634)); +#157=EDGE_LOOP('',(#635)); +#158=EDGE_LOOP('',(#636)); +#159=EDGE_LOOP('',(#637)); +#160=EDGE_LOOP('',(#638,#639,#640,#641)); +#161=EDGE_LOOP('',(#642,#643,#644,#645)); +#162=EDGE_LOOP('',(#646,#647,#648,#649)); +#163=EDGE_LOOP('',(#650,#651,#652,#653,#654,#655,#656,#657)); +#164=EDGE_LOOP('',(#658)); +#165=EDGE_LOOP('',(#659)); +#166=EDGE_LOOP('',(#660)); +#167=EDGE_LOOP('',(#661)); +#168=EDGE_LOOP('',(#662)); +#169=LINE('',#1056,#215); +#170=LINE('',#1062,#216); +#171=LINE('',#1068,#217); +#172=LINE('',#1074,#218); +#173=LINE('',#1080,#219); +#174=LINE('',#1086,#220); +#175=LINE('',#1092,#221); +#176=LINE('',#1098,#222); +#177=LINE('',#1104,#223); +#178=LINE('',#1110,#224); +#179=LINE('',#1116,#225); +#180=LINE('',#1122,#226); +#181=LINE('',#1128,#227); +#182=LINE('',#1134,#228); +#183=LINE('',#1140,#229); +#184=LINE('',#1146,#230); +#185=LINE('',#1153,#231); +#186=LINE('',#1156,#232); +#187=LINE('',#1162,#233); +#188=LINE('',#1165,#234); +#189=LINE('',#1168,#235); +#190=LINE('',#1170,#236); +#191=LINE('',#1171,#237); +#192=LINE('',#1176,#238); +#193=LINE('',#1180,#239); +#194=LINE('',#1182,#240); +#195=LINE('',#1184,#241); +#196=LINE('',#1188,#242); +#197=LINE('',#1198,#243); +#198=LINE('',#1202,#244); +#199=LINE('',#1204,#245); +#200=LINE('',#1206,#246); +#201=LINE('',#1210,#247); +#202=LINE('',#1213,#248); +#203=LINE('',#1215,#249); +#204=LINE('',#1216,#250); +#205=LINE('',#1221,#251); +#206=LINE('',#1227,#252); +#207=LINE('',#1233,#253); +#208=LINE('',#1235,#254); +#209=LINE('',#1237,#255); +#210=LINE('',#1239,#256); +#211=LINE('',#1241,#257); +#212=LINE('',#1244,#258); +#213=LINE('',#1246,#259); +#214=LINE('',#1248,#260); +#215=VECTOR('',#833,1.6); +#216=VECTOR('',#840,1.6); +#217=VECTOR('',#847,1.6); +#218=VECTOR('',#854,1.6); +#219=VECTOR('',#861,1.6); +#220=VECTOR('',#868,1.6); +#221=VECTOR('',#875,1.6); +#222=VECTOR('',#882,1.6); +#223=VECTOR('',#889,1.6); +#224=VECTOR('',#896,1.6); +#225=VECTOR('',#903,1.6); +#226=VECTOR('',#910,6.99999999999999); +#227=VECTOR('',#917,1.2645); +#228=VECTOR('',#924,1.2645); +#229=VECTOR('',#931,1.2645); +#230=VECTOR('',#938,1.2645); +#231=VECTOR('',#945,10.); +#232=VECTOR('',#948,10.); +#233=VECTOR('',#953,10.); +#234=VECTOR('',#956,10.); +#235=VECTOR('',#959,10.); +#236=VECTOR('',#960,10.); +#237=VECTOR('',#961,10.); +#238=VECTOR('',#966,10.); +#239=VECTOR('',#969,10.); +#240=VECTOR('',#970,10.); +#241=VECTOR('',#971,10.); +#242=VECTOR('',#974,10.); +#243=VECTOR('',#987,10.); +#244=VECTOR('',#990,10.); +#245=VECTOR('',#991,10.); +#246=VECTOR('',#992,10.); +#247=VECTOR('',#995,10.); +#248=VECTOR('',#998,10.); +#249=VECTOR('',#1001,10.); +#250=VECTOR('',#1002,10.); +#251=VECTOR('',#1007,10.); +#252=VECTOR('',#1014,10.); +#253=VECTOR('',#1025,10.); +#254=VECTOR('',#1028,10.); +#255=VECTOR('',#1031,10.); +#256=VECTOR('',#1034,10.); +#257=VECTOR('',#1037,10.); +#258=VECTOR('',#1042,10.); +#259=VECTOR('',#1045,10.); +#260=VECTOR('',#1048,10.); +#261=CIRCLE('',#740,1.6); +#262=CIRCLE('',#741,1.6); +#263=CIRCLE('',#743,1.6); +#264=CIRCLE('',#744,1.6); +#265=CIRCLE('',#746,1.6); +#266=CIRCLE('',#747,1.6); +#267=CIRCLE('',#749,1.6); +#268=CIRCLE('',#750,1.6); +#269=CIRCLE('',#752,1.6); +#270=CIRCLE('',#753,1.6); +#271=CIRCLE('',#755,1.6); +#272=CIRCLE('',#756,1.6); +#273=CIRCLE('',#758,1.6); +#274=CIRCLE('',#759,1.6); +#275=CIRCLE('',#761,1.6); +#276=CIRCLE('',#762,1.6); +#277=CIRCLE('',#764,1.6); +#278=CIRCLE('',#765,1.6); +#279=CIRCLE('',#767,1.6); +#280=CIRCLE('',#768,1.6); +#281=CIRCLE('',#770,1.6); +#282=CIRCLE('',#771,1.6); +#283=CIRCLE('',#773,6.99999999999999); +#284=CIRCLE('',#774,6.99999999999999); +#285=CIRCLE('',#776,1.2645); +#286=CIRCLE('',#777,1.2645); +#287=CIRCLE('',#779,1.2645); +#288=CIRCLE('',#780,1.2645); +#289=CIRCLE('',#782,1.2645); +#290=CIRCLE('',#783,1.2645); +#291=CIRCLE('',#785,1.2645); +#292=CIRCLE('',#786,1.2645); +#293=CIRCLE('',#788,17.5); +#294=CIRCLE('',#789,17.5); +#295=CIRCLE('',#791,3.50000000000001); +#296=CIRCLE('',#792,3.50000000000001); +#297=CIRCLE('',#800,28.5); +#298=CIRCLE('',#801,28.5); +#299=CIRCLE('',#809,21.5); +#300=CIRCLE('',#810,21.5); +#301=CIRCLE('',#812,3.49999999999998); +#302=CIRCLE('',#813,3.49999999999998); +#303=CIRCLE('',#815,28.5); +#304=CIRCLE('',#816,28.5); +#305=VERTEX_POINT('',#1053); +#306=VERTEX_POINT('',#1055); +#307=VERTEX_POINT('',#1059); +#308=VERTEX_POINT('',#1061); +#309=VERTEX_POINT('',#1065); +#310=VERTEX_POINT('',#1067); +#311=VERTEX_POINT('',#1071); +#312=VERTEX_POINT('',#1073); +#313=VERTEX_POINT('',#1077); +#314=VERTEX_POINT('',#1079); +#315=VERTEX_POINT('',#1083); +#316=VERTEX_POINT('',#1085); +#317=VERTEX_POINT('',#1089); +#318=VERTEX_POINT('',#1091); +#319=VERTEX_POINT('',#1095); +#320=VERTEX_POINT('',#1097); +#321=VERTEX_POINT('',#1101); +#322=VERTEX_POINT('',#1103); +#323=VERTEX_POINT('',#1107); +#324=VERTEX_POINT('',#1109); +#325=VERTEX_POINT('',#1113); +#326=VERTEX_POINT('',#1115); +#327=VERTEX_POINT('',#1119); +#328=VERTEX_POINT('',#1121); +#329=VERTEX_POINT('',#1125); +#330=VERTEX_POINT('',#1127); +#331=VERTEX_POINT('',#1131); +#332=VERTEX_POINT('',#1133); +#333=VERTEX_POINT('',#1137); +#334=VERTEX_POINT('',#1139); +#335=VERTEX_POINT('',#1143); +#336=VERTEX_POINT('',#1145); +#337=VERTEX_POINT('',#1149); +#338=VERTEX_POINT('',#1150); +#339=VERTEX_POINT('',#1152); +#340=VERTEX_POINT('',#1154); +#341=VERTEX_POINT('',#1158); +#342=VERTEX_POINT('',#1159); +#343=VERTEX_POINT('',#1161); +#344=VERTEX_POINT('',#1163); +#345=VERTEX_POINT('',#1167); +#346=VERTEX_POINT('',#1169); +#347=VERTEX_POINT('',#1173); +#348=VERTEX_POINT('',#1175); +#349=VERTEX_POINT('',#1177); +#350=VERTEX_POINT('',#1179); +#351=VERTEX_POINT('',#1181); +#352=VERTEX_POINT('',#1183); +#353=VERTEX_POINT('',#1185); +#354=VERTEX_POINT('',#1187); +#355=VERTEX_POINT('',#1194); +#356=VERTEX_POINT('',#1195); +#357=VERTEX_POINT('',#1197); +#358=VERTEX_POINT('',#1199); +#359=VERTEX_POINT('',#1201); +#360=VERTEX_POINT('',#1203); +#361=VERTEX_POINT('',#1205); +#362=VERTEX_POINT('',#1207); +#363=VERTEX_POINT('',#1209); +#364=VERTEX_POINT('',#1211); +#365=VERTEX_POINT('',#1218); +#366=VERTEX_POINT('',#1220); +#367=VERTEX_POINT('',#1224); +#368=VERTEX_POINT('',#1226); +#369=EDGE_CURVE('',#305,#305,#261,.T.); +#370=EDGE_CURVE('',#305,#306,#169,.T.); +#371=EDGE_CURVE('',#306,#306,#262,.T.); +#372=EDGE_CURVE('',#307,#307,#263,.T.); +#373=EDGE_CURVE('',#307,#308,#170,.T.); +#374=EDGE_CURVE('',#308,#308,#264,.T.); +#375=EDGE_CURVE('',#309,#309,#265,.T.); +#376=EDGE_CURVE('',#309,#310,#171,.T.); +#377=EDGE_CURVE('',#310,#310,#266,.T.); +#378=EDGE_CURVE('',#311,#311,#267,.T.); +#379=EDGE_CURVE('',#311,#312,#172,.T.); +#380=EDGE_CURVE('',#312,#312,#268,.T.); +#381=EDGE_CURVE('',#313,#313,#269,.T.); +#382=EDGE_CURVE('',#313,#314,#173,.T.); +#383=EDGE_CURVE('',#314,#314,#270,.T.); +#384=EDGE_CURVE('',#315,#315,#271,.T.); +#385=EDGE_CURVE('',#315,#316,#174,.T.); +#386=EDGE_CURVE('',#316,#316,#272,.T.); +#387=EDGE_CURVE('',#317,#317,#273,.T.); +#388=EDGE_CURVE('',#317,#318,#175,.T.); +#389=EDGE_CURVE('',#318,#318,#274,.T.); +#390=EDGE_CURVE('',#319,#319,#275,.T.); +#391=EDGE_CURVE('',#319,#320,#176,.T.); +#392=EDGE_CURVE('',#320,#320,#276,.T.); +#393=EDGE_CURVE('',#321,#321,#277,.T.); +#394=EDGE_CURVE('',#321,#322,#177,.T.); +#395=EDGE_CURVE('',#322,#322,#278,.T.); +#396=EDGE_CURVE('',#323,#323,#279,.T.); +#397=EDGE_CURVE('',#323,#324,#178,.T.); +#398=EDGE_CURVE('',#324,#324,#280,.T.); +#399=EDGE_CURVE('',#325,#325,#281,.T.); +#400=EDGE_CURVE('',#325,#326,#179,.T.); +#401=EDGE_CURVE('',#326,#326,#282,.T.); +#402=EDGE_CURVE('',#327,#327,#283,.T.); +#403=EDGE_CURVE('',#327,#328,#180,.T.); +#404=EDGE_CURVE('',#328,#328,#284,.T.); +#405=EDGE_CURVE('',#329,#329,#285,.T.); +#406=EDGE_CURVE('',#329,#330,#181,.T.); +#407=EDGE_CURVE('',#330,#330,#286,.T.); +#408=EDGE_CURVE('',#331,#331,#287,.T.); +#409=EDGE_CURVE('',#331,#332,#182,.T.); +#410=EDGE_CURVE('',#332,#332,#288,.T.); +#411=EDGE_CURVE('',#333,#333,#289,.T.); +#412=EDGE_CURVE('',#333,#334,#183,.T.); +#413=EDGE_CURVE('',#334,#334,#290,.T.); +#414=EDGE_CURVE('',#335,#335,#291,.T.); +#415=EDGE_CURVE('',#335,#336,#184,.T.); +#416=EDGE_CURVE('',#336,#336,#292,.T.); +#417=EDGE_CURVE('',#337,#338,#293,.T.); +#418=EDGE_CURVE('',#339,#337,#185,.T.); +#419=EDGE_CURVE('',#340,#339,#294,.T.); +#420=EDGE_CURVE('',#340,#338,#186,.T.); +#421=EDGE_CURVE('',#341,#342,#295,.T.); +#422=EDGE_CURVE('',#343,#341,#187,.T.); +#423=EDGE_CURVE('',#344,#343,#296,.T.); +#424=EDGE_CURVE('',#342,#344,#188,.T.); +#425=EDGE_CURVE('',#345,#337,#189,.T.); +#426=EDGE_CURVE('',#346,#345,#190,.T.); +#427=EDGE_CURVE('',#339,#346,#191,.T.); +#428=EDGE_CURVE('',#347,#345,#47,.T.); +#429=EDGE_CURVE('',#348,#347,#192,.T.); +#430=EDGE_CURVE('',#349,#348,#48,.T.); +#431=EDGE_CURVE('',#350,#349,#193,.T.); +#432=EDGE_CURVE('',#351,#350,#194,.T.); +#433=EDGE_CURVE('',#352,#351,#195,.T.); +#434=EDGE_CURVE('',#353,#352,#49,.T.); +#435=EDGE_CURVE('',#354,#353,#196,.T.); +#436=EDGE_CURVE('',#346,#354,#50,.T.); +#437=EDGE_CURVE('',#342,#350,#297,.T.); +#438=EDGE_CURVE('',#351,#344,#298,.T.); +#439=EDGE_CURVE('',#355,#356,#51,.T.); +#440=EDGE_CURVE('',#357,#355,#197,.T.); +#441=EDGE_CURVE('',#358,#357,#52,.T.); +#442=EDGE_CURVE('',#359,#358,#198,.T.); +#443=EDGE_CURVE('',#359,#360,#199,.T.); +#444=EDGE_CURVE('',#361,#360,#200,.T.); +#445=EDGE_CURVE('',#362,#361,#53,.T.); +#446=EDGE_CURVE('',#363,#362,#201,.T.); +#447=EDGE_CURVE('',#364,#363,#54,.T.); +#448=EDGE_CURVE('',#356,#364,#202,.T.); +#449=EDGE_CURVE('',#356,#340,#203,.T.); +#450=EDGE_CURVE('',#338,#364,#204,.T.); +#451=EDGE_CURVE('',#365,#341,#299,.T.); +#452=EDGE_CURVE('',#366,#365,#205,.T.); +#453=EDGE_CURVE('',#343,#366,#300,.T.); +#454=EDGE_CURVE('',#367,#365,#301,.T.); +#455=EDGE_CURVE('',#368,#367,#206,.T.); +#456=EDGE_CURVE('',#366,#368,#302,.T.); +#457=EDGE_CURVE('',#360,#367,#303,.T.); +#458=EDGE_CURVE('',#368,#359,#304,.T.); +#459=EDGE_CURVE('',#345,#364,#207,.T.); +#460=EDGE_CURVE('',#346,#356,#208,.T.); +#461=EDGE_CURVE('',#363,#347,#209,.T.); +#462=EDGE_CURVE('',#348,#362,#210,.T.); +#463=EDGE_CURVE('',#361,#349,#211,.T.); +#464=EDGE_CURVE('',#355,#354,#212,.T.); +#465=EDGE_CURVE('',#353,#357,#213,.T.); +#466=EDGE_CURVE('',#358,#352,#214,.T.); +#467=ORIENTED_EDGE('',*,*,#369,.F.); +#468=ORIENTED_EDGE('',*,*,#370,.T.); +#469=ORIENTED_EDGE('',*,*,#371,.F.); +#470=ORIENTED_EDGE('',*,*,#370,.F.); +#471=ORIENTED_EDGE('',*,*,#372,.F.); +#472=ORIENTED_EDGE('',*,*,#373,.T.); +#473=ORIENTED_EDGE('',*,*,#374,.F.); +#474=ORIENTED_EDGE('',*,*,#373,.F.); +#475=ORIENTED_EDGE('',*,*,#375,.F.); +#476=ORIENTED_EDGE('',*,*,#376,.T.); +#477=ORIENTED_EDGE('',*,*,#377,.F.); +#478=ORIENTED_EDGE('',*,*,#376,.F.); +#479=ORIENTED_EDGE('',*,*,#378,.F.); +#480=ORIENTED_EDGE('',*,*,#379,.T.); +#481=ORIENTED_EDGE('',*,*,#380,.F.); +#482=ORIENTED_EDGE('',*,*,#379,.F.); +#483=ORIENTED_EDGE('',*,*,#381,.F.); +#484=ORIENTED_EDGE('',*,*,#382,.T.); +#485=ORIENTED_EDGE('',*,*,#383,.F.); +#486=ORIENTED_EDGE('',*,*,#382,.F.); +#487=ORIENTED_EDGE('',*,*,#384,.F.); +#488=ORIENTED_EDGE('',*,*,#385,.T.); +#489=ORIENTED_EDGE('',*,*,#386,.F.); +#490=ORIENTED_EDGE('',*,*,#385,.F.); +#491=ORIENTED_EDGE('',*,*,#387,.F.); +#492=ORIENTED_EDGE('',*,*,#388,.T.); +#493=ORIENTED_EDGE('',*,*,#389,.F.); +#494=ORIENTED_EDGE('',*,*,#388,.F.); +#495=ORIENTED_EDGE('',*,*,#390,.F.); +#496=ORIENTED_EDGE('',*,*,#391,.T.); +#497=ORIENTED_EDGE('',*,*,#392,.F.); +#498=ORIENTED_EDGE('',*,*,#391,.F.); +#499=ORIENTED_EDGE('',*,*,#393,.F.); +#500=ORIENTED_EDGE('',*,*,#394,.T.); +#501=ORIENTED_EDGE('',*,*,#395,.F.); +#502=ORIENTED_EDGE('',*,*,#394,.F.); +#503=ORIENTED_EDGE('',*,*,#396,.F.); +#504=ORIENTED_EDGE('',*,*,#397,.T.); +#505=ORIENTED_EDGE('',*,*,#398,.F.); +#506=ORIENTED_EDGE('',*,*,#397,.F.); +#507=ORIENTED_EDGE('',*,*,#399,.F.); +#508=ORIENTED_EDGE('',*,*,#400,.T.); +#509=ORIENTED_EDGE('',*,*,#401,.F.); +#510=ORIENTED_EDGE('',*,*,#400,.F.); +#511=ORIENTED_EDGE('',*,*,#402,.F.); +#512=ORIENTED_EDGE('',*,*,#403,.T.); +#513=ORIENTED_EDGE('',*,*,#404,.F.); +#514=ORIENTED_EDGE('',*,*,#403,.F.); +#515=ORIENTED_EDGE('',*,*,#405,.F.); +#516=ORIENTED_EDGE('',*,*,#406,.T.); +#517=ORIENTED_EDGE('',*,*,#407,.F.); +#518=ORIENTED_EDGE('',*,*,#406,.F.); +#519=ORIENTED_EDGE('',*,*,#408,.F.); +#520=ORIENTED_EDGE('',*,*,#409,.T.); +#521=ORIENTED_EDGE('',*,*,#410,.F.); +#522=ORIENTED_EDGE('',*,*,#409,.F.); +#523=ORIENTED_EDGE('',*,*,#411,.F.); +#524=ORIENTED_EDGE('',*,*,#412,.T.); +#525=ORIENTED_EDGE('',*,*,#413,.F.); +#526=ORIENTED_EDGE('',*,*,#412,.F.); +#527=ORIENTED_EDGE('',*,*,#414,.F.); +#528=ORIENTED_EDGE('',*,*,#415,.T.); +#529=ORIENTED_EDGE('',*,*,#416,.F.); +#530=ORIENTED_EDGE('',*,*,#415,.F.); +#531=ORIENTED_EDGE('',*,*,#417,.F.); +#532=ORIENTED_EDGE('',*,*,#418,.F.); +#533=ORIENTED_EDGE('',*,*,#419,.F.); +#534=ORIENTED_EDGE('',*,*,#420,.T.); +#535=ORIENTED_EDGE('',*,*,#421,.F.); +#536=ORIENTED_EDGE('',*,*,#422,.F.); +#537=ORIENTED_EDGE('',*,*,#423,.F.); +#538=ORIENTED_EDGE('',*,*,#424,.F.); +#539=ORIENTED_EDGE('',*,*,#425,.F.); +#540=ORIENTED_EDGE('',*,*,#426,.F.); +#541=ORIENTED_EDGE('',*,*,#427,.F.); +#542=ORIENTED_EDGE('',*,*,#418,.T.); +#543=ORIENTED_EDGE('',*,*,#428,.F.); +#544=ORIENTED_EDGE('',*,*,#429,.F.); +#545=ORIENTED_EDGE('',*,*,#430,.F.); +#546=ORIENTED_EDGE('',*,*,#431,.F.); +#547=ORIENTED_EDGE('',*,*,#432,.F.); +#548=ORIENTED_EDGE('',*,*,#433,.F.); +#549=ORIENTED_EDGE('',*,*,#434,.F.); +#550=ORIENTED_EDGE('',*,*,#435,.F.); +#551=ORIENTED_EDGE('',*,*,#436,.F.); +#552=ORIENTED_EDGE('',*,*,#426,.T.); +#553=ORIENTED_EDGE('',*,*,#437,.F.); +#554=ORIENTED_EDGE('',*,*,#424,.T.); +#555=ORIENTED_EDGE('',*,*,#438,.F.); +#556=ORIENTED_EDGE('',*,*,#432,.T.); +#557=ORIENTED_EDGE('',*,*,#439,.F.); +#558=ORIENTED_EDGE('',*,*,#440,.F.); +#559=ORIENTED_EDGE('',*,*,#441,.F.); +#560=ORIENTED_EDGE('',*,*,#442,.F.); +#561=ORIENTED_EDGE('',*,*,#443,.T.); +#562=ORIENTED_EDGE('',*,*,#444,.F.); +#563=ORIENTED_EDGE('',*,*,#445,.F.); +#564=ORIENTED_EDGE('',*,*,#446,.F.); +#565=ORIENTED_EDGE('',*,*,#447,.F.); +#566=ORIENTED_EDGE('',*,*,#448,.F.); +#567=ORIENTED_EDGE('',*,*,#449,.F.); +#568=ORIENTED_EDGE('',*,*,#448,.T.); +#569=ORIENTED_EDGE('',*,*,#450,.F.); +#570=ORIENTED_EDGE('',*,*,#420,.F.); +#571=ORIENTED_EDGE('',*,*,#451,.F.); +#572=ORIENTED_EDGE('',*,*,#452,.F.); +#573=ORIENTED_EDGE('',*,*,#453,.F.); +#574=ORIENTED_EDGE('',*,*,#422,.T.); +#575=ORIENTED_EDGE('',*,*,#454,.F.); +#576=ORIENTED_EDGE('',*,*,#455,.F.); +#577=ORIENTED_EDGE('',*,*,#456,.F.); +#578=ORIENTED_EDGE('',*,*,#452,.T.); +#579=ORIENTED_EDGE('',*,*,#457,.F.); +#580=ORIENTED_EDGE('',*,*,#443,.F.); +#581=ORIENTED_EDGE('',*,*,#458,.F.); +#582=ORIENTED_EDGE('',*,*,#455,.T.); +#583=ORIENTED_EDGE('',*,*,#425,.T.); +#584=ORIENTED_EDGE('',*,*,#417,.T.); +#585=ORIENTED_EDGE('',*,*,#450,.T.); +#586=ORIENTED_EDGE('',*,*,#459,.F.); +#587=ORIENTED_EDGE('',*,*,#369,.T.); +#588=ORIENTED_EDGE('',*,*,#372,.T.); +#589=ORIENTED_EDGE('',*,*,#375,.T.); +#590=ORIENTED_EDGE('',*,*,#378,.T.); +#591=ORIENTED_EDGE('',*,*,#381,.T.); +#592=ORIENTED_EDGE('',*,*,#384,.T.); +#593=ORIENTED_EDGE('',*,*,#402,.T.); +#594=ORIENTED_EDGE('',*,*,#405,.T.); +#595=ORIENTED_EDGE('',*,*,#408,.T.); +#596=ORIENTED_EDGE('',*,*,#411,.T.); +#597=ORIENTED_EDGE('',*,*,#414,.T.); +#598=ORIENTED_EDGE('',*,*,#449,.T.); +#599=ORIENTED_EDGE('',*,*,#419,.T.); +#600=ORIENTED_EDGE('',*,*,#427,.T.); +#601=ORIENTED_EDGE('',*,*,#460,.T.); +#602=ORIENTED_EDGE('',*,*,#371,.T.); +#603=ORIENTED_EDGE('',*,*,#374,.T.); +#604=ORIENTED_EDGE('',*,*,#377,.T.); +#605=ORIENTED_EDGE('',*,*,#380,.T.); +#606=ORIENTED_EDGE('',*,*,#383,.T.); +#607=ORIENTED_EDGE('',*,*,#386,.T.); +#608=ORIENTED_EDGE('',*,*,#404,.T.); +#609=ORIENTED_EDGE('',*,*,#407,.T.); +#610=ORIENTED_EDGE('',*,*,#410,.T.); +#611=ORIENTED_EDGE('',*,*,#413,.T.); +#612=ORIENTED_EDGE('',*,*,#416,.T.); +#613=ORIENTED_EDGE('',*,*,#428,.T.); +#614=ORIENTED_EDGE('',*,*,#459,.T.); +#615=ORIENTED_EDGE('',*,*,#447,.T.); +#616=ORIENTED_EDGE('',*,*,#461,.T.); +#617=ORIENTED_EDGE('',*,*,#429,.T.); +#618=ORIENTED_EDGE('',*,*,#461,.F.); +#619=ORIENTED_EDGE('',*,*,#446,.T.); +#620=ORIENTED_EDGE('',*,*,#462,.F.); +#621=ORIENTED_EDGE('',*,*,#430,.T.); +#622=ORIENTED_EDGE('',*,*,#462,.T.); +#623=ORIENTED_EDGE('',*,*,#445,.T.); +#624=ORIENTED_EDGE('',*,*,#463,.T.); +#625=ORIENTED_EDGE('',*,*,#431,.T.); +#626=ORIENTED_EDGE('',*,*,#463,.F.); +#627=ORIENTED_EDGE('',*,*,#444,.T.); +#628=ORIENTED_EDGE('',*,*,#457,.T.); +#629=ORIENTED_EDGE('',*,*,#454,.T.); +#630=ORIENTED_EDGE('',*,*,#451,.T.); +#631=ORIENTED_EDGE('',*,*,#421,.T.); +#632=ORIENTED_EDGE('',*,*,#437,.T.); +#633=ORIENTED_EDGE('',*,*,#387,.T.); +#634=ORIENTED_EDGE('',*,*,#390,.T.); +#635=ORIENTED_EDGE('',*,*,#393,.T.); +#636=ORIENTED_EDGE('',*,*,#396,.T.); +#637=ORIENTED_EDGE('',*,*,#399,.T.); +#638=ORIENTED_EDGE('',*,*,#439,.T.); +#639=ORIENTED_EDGE('',*,*,#460,.F.); +#640=ORIENTED_EDGE('',*,*,#436,.T.); +#641=ORIENTED_EDGE('',*,*,#464,.F.); +#642=ORIENTED_EDGE('',*,*,#440,.T.); +#643=ORIENTED_EDGE('',*,*,#464,.T.); +#644=ORIENTED_EDGE('',*,*,#435,.T.); +#645=ORIENTED_EDGE('',*,*,#465,.T.); +#646=ORIENTED_EDGE('',*,*,#441,.T.); +#647=ORIENTED_EDGE('',*,*,#465,.F.); +#648=ORIENTED_EDGE('',*,*,#434,.T.); +#649=ORIENTED_EDGE('',*,*,#466,.F.); +#650=ORIENTED_EDGE('',*,*,#442,.T.); +#651=ORIENTED_EDGE('',*,*,#466,.T.); +#652=ORIENTED_EDGE('',*,*,#433,.T.); +#653=ORIENTED_EDGE('',*,*,#438,.T.); +#654=ORIENTED_EDGE('',*,*,#423,.T.); +#655=ORIENTED_EDGE('',*,*,#453,.T.); +#656=ORIENTED_EDGE('',*,*,#456,.T.); +#657=ORIENTED_EDGE('',*,*,#458,.T.); +#658=ORIENTED_EDGE('',*,*,#389,.T.); +#659=ORIENTED_EDGE('',*,*,#392,.T.); +#660=ORIENTED_EDGE('',*,*,#395,.T.); +#661=ORIENTED_EDGE('',*,*,#398,.T.); +#662=ORIENTED_EDGE('',*,*,#401,.T.); +#663=CYLINDRICAL_SURFACE('',#739,1.6); +#664=CYLINDRICAL_SURFACE('',#742,1.6); +#665=CYLINDRICAL_SURFACE('',#745,1.6); +#666=CYLINDRICAL_SURFACE('',#748,1.6); +#667=CYLINDRICAL_SURFACE('',#751,1.6); +#668=CYLINDRICAL_SURFACE('',#754,1.6); +#669=CYLINDRICAL_SURFACE('',#757,1.6); +#670=CYLINDRICAL_SURFACE('',#760,1.6); +#671=CYLINDRICAL_SURFACE('',#763,1.6); +#672=CYLINDRICAL_SURFACE('',#766,1.6); +#673=CYLINDRICAL_SURFACE('',#769,1.6); +#674=CYLINDRICAL_SURFACE('',#772,6.99999999999999); +#675=CYLINDRICAL_SURFACE('',#775,1.2645); +#676=CYLINDRICAL_SURFACE('',#778,1.2645); +#677=CYLINDRICAL_SURFACE('',#781,1.2645); +#678=CYLINDRICAL_SURFACE('',#784,1.2645); +#679=CYLINDRICAL_SURFACE('',#787,17.5); +#680=CYLINDRICAL_SURFACE('',#790,3.50000000000001); +#681=CYLINDRICAL_SURFACE('',#799,28.5); +#682=CYLINDRICAL_SURFACE('',#808,21.5); +#683=CYLINDRICAL_SURFACE('',#811,3.49999999999998); +#684=CYLINDRICAL_SURFACE('',#814,28.5); +#685=CYLINDRICAL_SURFACE('',#819,0.100000000000001); +#686=CYLINDRICAL_SURFACE('',#821,2.6); +#687=CYLINDRICAL_SURFACE('',#823,2.6); +#688=CYLINDRICAL_SURFACE('',#825,0.1); +#689=ADVANCED_FACE('',(#65),#663,.F.); +#690=ADVANCED_FACE('',(#66),#664,.F.); +#691=ADVANCED_FACE('',(#67),#665,.F.); +#692=ADVANCED_FACE('',(#68),#666,.F.); +#693=ADVANCED_FACE('',(#69),#667,.F.); +#694=ADVANCED_FACE('',(#70),#668,.F.); +#695=ADVANCED_FACE('',(#71),#669,.F.); +#696=ADVANCED_FACE('',(#72),#670,.F.); +#697=ADVANCED_FACE('',(#73),#671,.F.); +#698=ADVANCED_FACE('',(#74),#672,.F.); +#699=ADVANCED_FACE('',(#75),#673,.F.); +#700=ADVANCED_FACE('',(#76),#674,.F.); +#701=ADVANCED_FACE('',(#77),#675,.F.); +#702=ADVANCED_FACE('',(#78),#676,.F.); +#703=ADVANCED_FACE('',(#79),#677,.F.); +#704=ADVANCED_FACE('',(#80),#678,.F.); +#705=ADVANCED_FACE('',(#81),#679,.T.); +#706=ADVANCED_FACE('',(#82),#680,.T.); +#707=ADVANCED_FACE('',(#83),#55,.F.); +#708=ADVANCED_FACE('',(#84),#56,.F.); +#709=ADVANCED_FACE('',(#85),#681,.T.); +#710=ADVANCED_FACE('',(#86),#57,.F.); +#711=ADVANCED_FACE('',(#87),#58,.F.); +#712=ADVANCED_FACE('',(#88),#682,.F.); +#713=ADVANCED_FACE('',(#89),#683,.T.); +#714=ADVANCED_FACE('',(#90),#684,.T.); +#715=ADVANCED_FACE('',(#91,#15,#16,#17,#18,#19,#20,#21,#22,#23,#24,#25), +#59,.F.); +#716=ADVANCED_FACE('',(#92,#26,#27,#28,#29,#30,#31,#32,#33,#34,#35,#36), +#60,.T.); +#717=ADVANCED_FACE('',(#93),#685,.F.); +#718=ADVANCED_FACE('',(#94),#61,.F.); +#719=ADVANCED_FACE('',(#95),#686,.T.); +#720=ADVANCED_FACE('',(#96,#37,#38,#39,#40,#41),#62,.F.); +#721=ADVANCED_FACE('',(#97),#687,.T.); +#722=ADVANCED_FACE('',(#98),#63,.T.); +#723=ADVANCED_FACE('',(#99),#688,.F.); +#724=ADVANCED_FACE('',(#100,#42,#43,#44,#45,#46),#64,.T.); +#725=CLOSED_SHELL('',(#689,#690,#691,#692,#693,#694,#695,#696,#697,#698, +#699,#700,#701,#702,#703,#704,#705,#706,#707,#708,#709,#710,#711,#712,#713, +#714,#715,#716,#717,#718,#719,#720,#721,#722,#723,#724)); +#726=DERIVED_UNIT_ELEMENT(#728,1.); +#727=DERIVED_UNIT_ELEMENT(#1255,-3.); +#728=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT(.KILO.,.GRAM.) +); +#729=DERIVED_UNIT((#726,#727)); +#730=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(7850.),#729); +#731=PROPERTY_DEFINITION_REPRESENTATION(#736,#733); +#732=PROPERTY_DEFINITION_REPRESENTATION(#737,#734); +#733=REPRESENTATION('material name',(#735),#1252); +#734=REPRESENTATION('density',(#730),#1252); +#735=DESCRIPTIVE_REPRESENTATION_ITEM('Steel','Steel'); +#736=PROPERTY_DEFINITION('material property','material name',#1262); +#737=PROPERTY_DEFINITION('material property','density of part',#1262); +#738=AXIS2_PLACEMENT_3D('',#1051,#827,#828); +#739=AXIS2_PLACEMENT_3D('',#1052,#829,#830); +#740=AXIS2_PLACEMENT_3D('',#1054,#831,#832); +#741=AXIS2_PLACEMENT_3D('',#1057,#834,#835); +#742=AXIS2_PLACEMENT_3D('',#1058,#836,#837); +#743=AXIS2_PLACEMENT_3D('',#1060,#838,#839); +#744=AXIS2_PLACEMENT_3D('',#1063,#841,#842); +#745=AXIS2_PLACEMENT_3D('',#1064,#843,#844); +#746=AXIS2_PLACEMENT_3D('',#1066,#845,#846); +#747=AXIS2_PLACEMENT_3D('',#1069,#848,#849); +#748=AXIS2_PLACEMENT_3D('',#1070,#850,#851); +#749=AXIS2_PLACEMENT_3D('',#1072,#852,#853); +#750=AXIS2_PLACEMENT_3D('',#1075,#855,#856); +#751=AXIS2_PLACEMENT_3D('',#1076,#857,#858); +#752=AXIS2_PLACEMENT_3D('',#1078,#859,#860); +#753=AXIS2_PLACEMENT_3D('',#1081,#862,#863); +#754=AXIS2_PLACEMENT_3D('',#1082,#864,#865); +#755=AXIS2_PLACEMENT_3D('',#1084,#866,#867); +#756=AXIS2_PLACEMENT_3D('',#1087,#869,#870); +#757=AXIS2_PLACEMENT_3D('',#1088,#871,#872); +#758=AXIS2_PLACEMENT_3D('',#1090,#873,#874); +#759=AXIS2_PLACEMENT_3D('',#1093,#876,#877); +#760=AXIS2_PLACEMENT_3D('',#1094,#878,#879); +#761=AXIS2_PLACEMENT_3D('',#1096,#880,#881); +#762=AXIS2_PLACEMENT_3D('',#1099,#883,#884); +#763=AXIS2_PLACEMENT_3D('',#1100,#885,#886); +#764=AXIS2_PLACEMENT_3D('',#1102,#887,#888); +#765=AXIS2_PLACEMENT_3D('',#1105,#890,#891); +#766=AXIS2_PLACEMENT_3D('',#1106,#892,#893); +#767=AXIS2_PLACEMENT_3D('',#1108,#894,#895); +#768=AXIS2_PLACEMENT_3D('',#1111,#897,#898); +#769=AXIS2_PLACEMENT_3D('',#1112,#899,#900); +#770=AXIS2_PLACEMENT_3D('',#1114,#901,#902); +#771=AXIS2_PLACEMENT_3D('',#1117,#904,#905); +#772=AXIS2_PLACEMENT_3D('',#1118,#906,#907); +#773=AXIS2_PLACEMENT_3D('',#1120,#908,#909); +#774=AXIS2_PLACEMENT_3D('',#1123,#911,#912); +#775=AXIS2_PLACEMENT_3D('',#1124,#913,#914); +#776=AXIS2_PLACEMENT_3D('',#1126,#915,#916); +#777=AXIS2_PLACEMENT_3D('',#1129,#918,#919); +#778=AXIS2_PLACEMENT_3D('',#1130,#920,#921); +#779=AXIS2_PLACEMENT_3D('',#1132,#922,#923); +#780=AXIS2_PLACEMENT_3D('',#1135,#925,#926); +#781=AXIS2_PLACEMENT_3D('',#1136,#927,#928); +#782=AXIS2_PLACEMENT_3D('',#1138,#929,#930); +#783=AXIS2_PLACEMENT_3D('',#1141,#932,#933); +#784=AXIS2_PLACEMENT_3D('',#1142,#934,#935); +#785=AXIS2_PLACEMENT_3D('',#1144,#936,#937); +#786=AXIS2_PLACEMENT_3D('',#1147,#939,#940); +#787=AXIS2_PLACEMENT_3D('',#1148,#941,#942); +#788=AXIS2_PLACEMENT_3D('',#1151,#943,#944); +#789=AXIS2_PLACEMENT_3D('',#1155,#946,#947); +#790=AXIS2_PLACEMENT_3D('',#1157,#949,#950); +#791=AXIS2_PLACEMENT_3D('',#1160,#951,#952); +#792=AXIS2_PLACEMENT_3D('',#1164,#954,#955); +#793=AXIS2_PLACEMENT_3D('',#1166,#957,#958); +#794=AXIS2_PLACEMENT_3D('',#1172,#962,#963); +#795=AXIS2_PLACEMENT_3D('',#1174,#964,#965); +#796=AXIS2_PLACEMENT_3D('',#1178,#967,#968); +#797=AXIS2_PLACEMENT_3D('',#1186,#972,#973); +#798=AXIS2_PLACEMENT_3D('',#1189,#975,#976); +#799=AXIS2_PLACEMENT_3D('',#1190,#977,#978); +#800=AXIS2_PLACEMENT_3D('',#1191,#979,#980); +#801=AXIS2_PLACEMENT_3D('',#1192,#981,#982); +#802=AXIS2_PLACEMENT_3D('',#1193,#983,#984); +#803=AXIS2_PLACEMENT_3D('',#1196,#985,#986); +#804=AXIS2_PLACEMENT_3D('',#1200,#988,#989); +#805=AXIS2_PLACEMENT_3D('',#1208,#993,#994); +#806=AXIS2_PLACEMENT_3D('',#1212,#996,#997); +#807=AXIS2_PLACEMENT_3D('',#1214,#999,#1000); +#808=AXIS2_PLACEMENT_3D('',#1217,#1003,#1004); +#809=AXIS2_PLACEMENT_3D('',#1219,#1005,#1006); +#810=AXIS2_PLACEMENT_3D('',#1222,#1008,#1009); +#811=AXIS2_PLACEMENT_3D('',#1223,#1010,#1011); +#812=AXIS2_PLACEMENT_3D('',#1225,#1012,#1013); +#813=AXIS2_PLACEMENT_3D('',#1228,#1015,#1016); +#814=AXIS2_PLACEMENT_3D('',#1229,#1017,#1018); +#815=AXIS2_PLACEMENT_3D('',#1230,#1019,#1020); +#816=AXIS2_PLACEMENT_3D('',#1231,#1021,#1022); +#817=AXIS2_PLACEMENT_3D('',#1232,#1023,#1024); +#818=AXIS2_PLACEMENT_3D('',#1234,#1026,#1027); +#819=AXIS2_PLACEMENT_3D('',#1236,#1029,#1030); +#820=AXIS2_PLACEMENT_3D('',#1238,#1032,#1033); +#821=AXIS2_PLACEMENT_3D('',#1240,#1035,#1036); +#822=AXIS2_PLACEMENT_3D('',#1242,#1038,#1039); +#823=AXIS2_PLACEMENT_3D('',#1243,#1040,#1041); +#824=AXIS2_PLACEMENT_3D('',#1245,#1043,#1044); +#825=AXIS2_PLACEMENT_3D('',#1247,#1046,#1047); +#826=AXIS2_PLACEMENT_3D('',#1249,#1049,#1050); +#827=DIRECTION('axis',(0.,0.,1.)); +#828=DIRECTION('refdir',(1.,0.,0.)); +#829=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#830=DIRECTION('ref_axis',(0.,1.,0.)); +#831=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#832=DIRECTION('ref_axis',(0.,1.,0.)); +#833=DIRECTION('',(-1.,0.,-3.80647894157196E-16)); +#834=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#835=DIRECTION('ref_axis',(0.,1.,0.)); +#836=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#837=DIRECTION('ref_axis',(0.,1.,0.)); +#838=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#839=DIRECTION('ref_axis',(0.,1.,0.)); +#840=DIRECTION('',(-1.,0.,-3.80647894157196E-16)); +#841=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#842=DIRECTION('ref_axis',(0.,1.,0.)); +#843=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#844=DIRECTION('ref_axis',(0.,1.,0.)); +#845=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#846=DIRECTION('ref_axis',(0.,1.,0.)); +#847=DIRECTION('',(-1.,0.,-3.80647894157196E-16)); +#848=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#849=DIRECTION('ref_axis',(0.,1.,0.)); +#850=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#851=DIRECTION('ref_axis',(0.,1.,0.)); +#852=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#853=DIRECTION('ref_axis',(0.,1.,0.)); +#854=DIRECTION('',(-1.,0.,-3.80647894157196E-16)); +#855=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#856=DIRECTION('ref_axis',(0.,1.,0.)); +#857=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#858=DIRECTION('ref_axis',(0.,1.,0.)); +#859=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#860=DIRECTION('ref_axis',(0.,1.,0.)); +#861=DIRECTION('',(-1.,0.,-3.80647894157196E-16)); +#862=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#863=DIRECTION('ref_axis',(0.,1.,0.)); +#864=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#865=DIRECTION('ref_axis',(0.,1.,0.)); +#866=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#867=DIRECTION('ref_axis',(0.,1.,0.)); +#868=DIRECTION('',(-1.,0.,-3.80647894157196E-16)); +#869=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#870=DIRECTION('ref_axis',(0.,1.,0.)); +#871=DIRECTION('center_axis',(-1.,0.,0.)); +#872=DIRECTION('ref_axis',(0.,1.,0.)); +#873=DIRECTION('center_axis',(-1.,0.,0.)); +#874=DIRECTION('ref_axis',(0.,1.,0.)); +#875=DIRECTION('',(-1.,0.,0.)); +#876=DIRECTION('center_axis',(1.,0.,0.)); +#877=DIRECTION('ref_axis',(0.,1.,0.)); +#878=DIRECTION('center_axis',(-1.,0.,0.)); +#879=DIRECTION('ref_axis',(0.,1.,0.)); +#880=DIRECTION('center_axis',(-1.,0.,0.)); +#881=DIRECTION('ref_axis',(0.,1.,0.)); +#882=DIRECTION('',(-1.,0.,0.)); +#883=DIRECTION('center_axis',(1.,0.,0.)); +#884=DIRECTION('ref_axis',(0.,1.,0.)); +#885=DIRECTION('center_axis',(-1.,0.,0.)); +#886=DIRECTION('ref_axis',(0.,1.,0.)); +#887=DIRECTION('center_axis',(-1.,0.,0.)); +#888=DIRECTION('ref_axis',(0.,1.,0.)); +#889=DIRECTION('',(-1.,0.,0.)); +#890=DIRECTION('center_axis',(1.,0.,0.)); +#891=DIRECTION('ref_axis',(0.,1.,0.)); +#892=DIRECTION('center_axis',(-1.,0.,0.)); +#893=DIRECTION('ref_axis',(0.,1.,0.)); +#894=DIRECTION('center_axis',(-1.,0.,0.)); +#895=DIRECTION('ref_axis',(0.,1.,0.)); +#896=DIRECTION('',(-1.,0.,0.)); +#897=DIRECTION('center_axis',(1.,0.,0.)); +#898=DIRECTION('ref_axis',(0.,1.,0.)); +#899=DIRECTION('center_axis',(-1.,0.,0.)); +#900=DIRECTION('ref_axis',(0.,1.,0.)); +#901=DIRECTION('center_axis',(-1.,0.,0.)); +#902=DIRECTION('ref_axis',(0.,1.,0.)); +#903=DIRECTION('',(-1.,0.,0.)); +#904=DIRECTION('center_axis',(1.,0.,0.)); +#905=DIRECTION('ref_axis',(0.,1.,0.)); +#906=DIRECTION('center_axis',(-1.,0.,0.)); +#907=DIRECTION('ref_axis',(0.,0.,-1.)); +#908=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#909=DIRECTION('ref_axis',(0.,0.,-1.)); +#910=DIRECTION('',(-1.,0.,0.)); +#911=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#912=DIRECTION('ref_axis',(0.,0.,-1.)); +#913=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#914=DIRECTION('ref_axis',(0.,1.,0.)); +#915=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#916=DIRECTION('ref_axis',(0.,1.,0.)); +#917=DIRECTION('',(-1.,0.,-3.80647894157197E-16)); +#918=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#919=DIRECTION('ref_axis',(0.,1.,0.)); +#920=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#921=DIRECTION('ref_axis',(0.,1.,0.)); +#922=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#923=DIRECTION('ref_axis',(0.,1.,0.)); +#924=DIRECTION('',(-1.,0.,-3.80647894157197E-16)); +#925=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#926=DIRECTION('ref_axis',(0.,1.,0.)); +#927=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#928=DIRECTION('ref_axis',(0.,1.,0.)); +#929=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#930=DIRECTION('ref_axis',(0.,1.,0.)); +#931=DIRECTION('',(-1.,0.,-3.80647894157197E-16)); +#932=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#933=DIRECTION('ref_axis',(0.,1.,0.)); +#934=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#935=DIRECTION('ref_axis',(0.,1.,0.)); +#936=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#937=DIRECTION('ref_axis',(0.,1.,0.)); +#938=DIRECTION('',(-1.,0.,-3.80647894157197E-16)); +#939=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#940=DIRECTION('ref_axis',(0.,1.,0.)); +#941=DIRECTION('center_axis',(-1.,0.,0.)); +#942=DIRECTION('ref_axis',(0.,0.,-1.)); +#943=DIRECTION('center_axis',(1.,0.,3.80647894157197E-16)); +#944=DIRECTION('ref_axis',(0.,0.,-1.)); +#945=DIRECTION('',(1.,0.,0.)); +#946=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#947=DIRECTION('ref_axis',(0.,0.,-1.)); +#948=DIRECTION('',(1.,0.,0.)); +#949=DIRECTION('center_axis',(-1.,0.,0.)); +#950=DIRECTION('ref_axis',(0.,0.500000000000001,0.866025403784438)); +#951=DIRECTION('center_axis',(1.,0.,0.)); +#952=DIRECTION('ref_axis',(0.,0.,-1.)); +#953=DIRECTION('',(1.,0.,0.)); +#954=DIRECTION('center_axis',(-1.,0.,0.)); +#955=DIRECTION('ref_axis',(0.,0.,-1.)); +#956=DIRECTION('',(-1.,0.,0.)); +#957=DIRECTION('center_axis',(0.,1.,8.41078048958452E-18)); +#958=DIRECTION('ref_axis',(0.,8.41078048958452E-18,-1.)); +#959=DIRECTION('',(3.80647894157197E-16,8.41078048958452E-18,-1.)); +#960=DIRECTION('',(1.,0.,0.)); +#961=DIRECTION('',(-3.80647894157197E-16,-8.41078048958452E-18,1.)); +#962=DIRECTION('center_axis',(0.,0.978496668404042,0.206262623667475)); +#963=DIRECTION('ref_axis',(0.,0.206262623667475,-0.978496668404042)); +#964=DIRECTION('center_axis',(0.,-0.978496668404042,-0.206262623667475)); +#965=DIRECTION('ref_axis',(-5.09226342553672E-16,-0.206262623667475,0.978496668404042)); +#966=DIRECTION('',(-0.491871114041505,0.179586270873585,-0.851945760295389)); +#967=DIRECTION('center_axis',(0.,0.978496668404042,0.206262623667475)); +#968=DIRECTION('ref_axis',(5.2228342826018E-16,0.206262623667475,-0.978496668404042)); +#969=DIRECTION('',(0.,0.206262623667475,-0.978496668404042)); +#970=DIRECTION('',(1.,0.,0.)); +#971=DIRECTION('',(0.,-0.206262623667475,0.978496668404042)); +#972=DIRECTION('center_axis',(0.,-0.978496668404042,-0.206262623667475)); +#973=DIRECTION('ref_axis',(7.63839513830513E-16,0.206262623667475,-0.978496668404042)); +#974=DIRECTION('',(0.491871114041505,-0.179586270873585,0.851945760295389)); +#975=DIRECTION('center_axis',(0.,0.978496668404042,0.206262623667475)); +#976=DIRECTION('ref_axis',(-5.2228342826018E-16,-0.206262623667475,0.978496668404042)); +#977=DIRECTION('center_axis',(-1.,0.,0.)); +#978=DIRECTION('ref_axis',(0.,0.,-1.)); +#979=DIRECTION('center_axis',(1.,0.,0.)); +#980=DIRECTION('ref_axis',(0.,0.,-1.)); +#981=DIRECTION('center_axis',(-1.,0.,0.)); +#982=DIRECTION('ref_axis',(0.,0.,-1.)); +#983=DIRECTION('center_axis',(0.,-0.978496668404042,0.206262623667475)); +#984=DIRECTION('ref_axis',(0.,0.206262623667475,0.978496668404042)); +#985=DIRECTION('center_axis',(0.,-0.978496668404042,0.206262623667475)); +#986=DIRECTION('ref_axis',(-2.6114171413009E-16,0.206262623667475,0.978496668404042)); +#987=DIRECTION('',(-0.491871114041505,-0.179586270873585,-0.851945760295389)); +#988=DIRECTION('center_axis',(0.,0.978496668404042,-0.206262623667475)); +#989=DIRECTION('ref_axis',(-1.27306585638419E-16,-0.206262623667475,-0.978496668404042)); +#990=DIRECTION('',(0.,-0.206262623667475,-0.978496668404042)); +#991=DIRECTION('',(1.,0.,0.)); +#992=DIRECTION('',(0.,0.206262623667475,0.978496668404042)); +#993=DIRECTION('center_axis',(0.,-0.978496668404042,0.206262623667475)); +#994=DIRECTION('ref_axis',(-5.2228342826018E-16,-0.206262623667475,-0.978496668404042)); +#995=DIRECTION('',(0.491871114041505,0.179586270873585,0.851945760295389)); +#996=DIRECTION('center_axis',(0.,0.978496668404042,-0.206262623667475)); +#997=DIRECTION('ref_axis',(1.69742114184557E-16,0.206262623667475,0.978496668404042)); +#998=DIRECTION('',(1.,0.,0.)); +#999=DIRECTION('center_axis',(0.,-1.,0.)); +#1000=DIRECTION('ref_axis',(0.,0.,1.)); +#1001=DIRECTION('',(3.80647894157197E-16,0.,-1.)); +#1002=DIRECTION('',(-3.80647894157197E-16,0.,1.)); +#1003=DIRECTION('center_axis',(-1.,0.,0.)); +#1004=DIRECTION('ref_axis',(0.,0.,-1.)); +#1005=DIRECTION('center_axis',(-1.,0.,0.)); +#1006=DIRECTION('ref_axis',(0.,0.,-1.)); +#1007=DIRECTION('',(1.,0.,0.)); +#1008=DIRECTION('center_axis',(1.,0.,0.)); +#1009=DIRECTION('ref_axis',(0.,0.,-1.)); +#1010=DIRECTION('center_axis',(-1.,0.,0.)); +#1011=DIRECTION('ref_axis',(0.,-0.499999999999999,0.866025403784439)); +#1012=DIRECTION('center_axis',(1.,0.,0.)); +#1013=DIRECTION('ref_axis',(0.,0.,-1.)); +#1014=DIRECTION('',(1.,0.,0.)); +#1015=DIRECTION('center_axis',(-1.,0.,0.)); +#1016=DIRECTION('ref_axis',(0.,0.,-1.)); +#1017=DIRECTION('center_axis',(-1.,0.,0.)); +#1018=DIRECTION('ref_axis',(0.,0.,-1.)); +#1019=DIRECTION('center_axis',(1.,0.,0.)); +#1020=DIRECTION('ref_axis',(0.,0.,-1.)); +#1021=DIRECTION('center_axis',(-1.,0.,0.)); +#1022=DIRECTION('ref_axis',(0.,0.,-1.)); +#1023=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#1024=DIRECTION('ref_axis',(-3.80647894157197E-16,0.,1.)); +#1025=DIRECTION('',(0.,1.,0.)); +#1026=DIRECTION('center_axis',(-1.,0.,-3.80647894157197E-16)); +#1027=DIRECTION('ref_axis',(-3.80647894157197E-16,0.,1.)); +#1028=DIRECTION('',(0.,1.,0.)); +#1029=DIRECTION('center_axis',(0.,1.,0.)); +#1030=DIRECTION('ref_axis',(-0.965925826289068,0.,0.258819045102523)); +#1031=DIRECTION('',(0.,-1.,0.)); +#1032=DIRECTION('center_axis',(-0.866025403784438,0.,0.500000000000001)); +#1033=DIRECTION('ref_axis',(0.500000000000001,0.,0.866025403784438)); +#1034=DIRECTION('',(0.,1.,0.)); +#1035=DIRECTION('center_axis',(0.,1.,0.)); +#1036=DIRECTION('ref_axis',(0.96592582628907,0.,-0.258819045102516)); +#1037=DIRECTION('',(0.,-1.,0.)); +#1038=DIRECTION('center_axis',(-1.,0.,0.)); +#1039=DIRECTION('ref_axis',(0.,0.,1.)); +#1040=DIRECTION('center_axis',(0.,1.,0.)); +#1041=DIRECTION('ref_axis',(-0.965925826289068,0.,0.258819045102523)); +#1042=DIRECTION('',(0.,-1.,0.)); +#1043=DIRECTION('center_axis',(-0.866025403784438,0.,0.500000000000001)); +#1044=DIRECTION('ref_axis',(0.500000000000001,0.,0.866025403784438)); +#1045=DIRECTION('',(0.,1.,0.)); +#1046=DIRECTION('center_axis',(0.,1.,0.)); +#1047=DIRECTION('ref_axis',(0.96592582628907,0.,-0.258819045102515)); +#1048=DIRECTION('',(0.,-1.,0.)); +#1049=DIRECTION('center_axis',(-1.,0.,0.)); +#1050=DIRECTION('ref_axis',(0.,0.,1.)); +#1051=CARTESIAN_POINT('',(0.,0.,0.)); +#1052=CARTESIAN_POINT('Origin',(-14.6,-12.5000000000001,-159.154482671904)); +#1053=CARTESIAN_POINT('',(-9.60000000000001,-14.1000000000001,-159.154482671904)); +#1054=CARTESIAN_POINT('Origin',(-9.60000000000001,-12.5000000000001,-159.154482671904)); +#1055=CARTESIAN_POINT('',(-12.1,-14.1000000000001,-159.154482671904)); +#1056=CARTESIAN_POINT('',(-14.6,-14.1000000000001,-159.154482671904)); +#1057=CARTESIAN_POINT('Origin',(-12.1,-12.5000000000001,-159.154482671904)); +#1058=CARTESIAN_POINT('Origin',(-14.6,12.5,-112.154482671904)); +#1059=CARTESIAN_POINT('',(-9.60000000000002,10.9,-112.154482671904)); +#1060=CARTESIAN_POINT('Origin',(-9.60000000000002,12.5,-112.154482671904)); +#1061=CARTESIAN_POINT('',(-12.1,10.9,-112.154482671904)); +#1062=CARTESIAN_POINT('',(-14.6,10.9,-112.154482671904)); +#1063=CARTESIAN_POINT('Origin',(-12.1,12.5,-112.154482671904)); +#1064=CARTESIAN_POINT('Origin',(-14.6,12.5,-65.1544826719044)); +#1065=CARTESIAN_POINT('',(-9.60000000000004,10.9,-65.1544826719044)); +#1066=CARTESIAN_POINT('Origin',(-9.60000000000004,12.5,-65.1544826719044)); +#1067=CARTESIAN_POINT('',(-12.1,10.9,-65.1544826719044)); +#1068=CARTESIAN_POINT('',(-14.6,10.9,-65.1544826719044)); +#1069=CARTESIAN_POINT('Origin',(-12.1,12.5,-65.1544826719044)); +#1070=CARTESIAN_POINT('Origin',(-14.6,-12.5000000000001,-65.1544826719044)); +#1071=CARTESIAN_POINT('',(-9.60000000000004,-14.1000000000001,-65.1544826719044)); +#1072=CARTESIAN_POINT('Origin',(-9.60000000000004,-12.5000000000001,-65.1544826719044)); +#1073=CARTESIAN_POINT('',(-12.1,-14.1000000000001,-65.1544826719044)); +#1074=CARTESIAN_POINT('',(-14.6,-14.1000000000001,-65.1544826719044)); +#1075=CARTESIAN_POINT('Origin',(-12.1,-12.5000000000001,-65.1544826719044)); +#1076=CARTESIAN_POINT('Origin',(-14.6,-12.5000000000001,-112.154482671904)); +#1077=CARTESIAN_POINT('',(-9.60000000000002,-14.1000000000001,-112.154482671904)); +#1078=CARTESIAN_POINT('Origin',(-9.60000000000002,-12.5000000000001,-112.154482671904)); +#1079=CARTESIAN_POINT('',(-12.1,-14.1000000000001,-112.154482671904)); +#1080=CARTESIAN_POINT('',(-14.6,-14.1000000000001,-112.154482671904)); +#1081=CARTESIAN_POINT('Origin',(-12.1,-12.5000000000001,-112.154482671904)); +#1082=CARTESIAN_POINT('Origin',(-14.6,12.5000000000001,-159.154482671904)); +#1083=CARTESIAN_POINT('',(-9.60000000000001,10.9000000000001,-159.154482671904)); +#1084=CARTESIAN_POINT('Origin',(-9.60000000000001,12.5000000000001,-159.154482671904)); +#1085=CARTESIAN_POINT('',(-12.1,10.9000000000001,-159.154482671904)); +#1086=CARTESIAN_POINT('',(-14.6,10.9000000000001,-159.154482671904)); +#1087=CARTESIAN_POINT('Origin',(-12.1,12.5000000000001,-159.154482671904)); +#1088=CARTESIAN_POINT('Origin',(-497.5,-21.650635094611,-12.5)); +#1089=CARTESIAN_POINT('',(2.5,-23.250635094611,-12.5)); +#1090=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,-12.5)); +#1091=CARTESIAN_POINT('',(0.,-23.250635094611,-12.5)); +#1092=CARTESIAN_POINT('',(-497.5,-23.250635094611,-12.5)); +#1093=CARTESIAN_POINT('Origin',(0.,-21.650635094611,-12.5)); +#1094=CARTESIAN_POINT('Origin',(-497.5,21.6506350946109,-12.5)); +#1095=CARTESIAN_POINT('',(2.5,20.0506350946109,-12.5)); +#1096=CARTESIAN_POINT('Origin',(2.5,21.6506350946109,-12.5)); +#1097=CARTESIAN_POINT('',(0.,20.0506350946109,-12.5)); +#1098=CARTESIAN_POINT('',(-497.5,20.0506350946109,-12.5)); +#1099=CARTESIAN_POINT('Origin',(0.,21.6506350946109,-12.5)); +#1100=CARTESIAN_POINT('Origin',(-497.5,21.650635094611,12.5)); +#1101=CARTESIAN_POINT('',(2.5,20.050635094611,12.5)); +#1102=CARTESIAN_POINT('Origin',(2.5,21.650635094611,12.5)); +#1103=CARTESIAN_POINT('',(0.,20.050635094611,12.5)); +#1104=CARTESIAN_POINT('',(-497.5,20.050635094611,12.5)); +#1105=CARTESIAN_POINT('Origin',(0.,21.650635094611,12.5)); +#1106=CARTESIAN_POINT('Origin',(-497.5,-2.55951181021797E-14,-25.)); +#1107=CARTESIAN_POINT('',(2.5,-1.60000000000003,-25.)); +#1108=CARTESIAN_POINT('Origin',(2.5,-2.55951181021797E-14,-25.)); +#1109=CARTESIAN_POINT('',(0.,-1.60000000000003,-25.)); +#1110=CARTESIAN_POINT('',(-497.5,-1.60000000000003,-25.)); +#1111=CARTESIAN_POINT('Origin',(0.,-2.55951181021797E-14,-25.)); +#1112=CARTESIAN_POINT('Origin',(-497.5,-21.650635094611,12.5)); +#1113=CARTESIAN_POINT('',(2.5,-23.250635094611,12.5)); +#1114=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,12.5)); +#1115=CARTESIAN_POINT('',(0.,-23.250635094611,12.5)); +#1116=CARTESIAN_POINT('',(-497.5,-23.250635094611,12.5)); +#1117=CARTESIAN_POINT('Origin',(0.,-21.650635094611,12.5)); +#1118=CARTESIAN_POINT('Origin',(-9.6,1.00421037445208E-14,-184.)); +#1119=CARTESIAN_POINT('',(-9.6,9.1848509851177E-15,-177.)); +#1120=CARTESIAN_POINT('Origin',(-9.59999999999999,1.00421037445208E-14, +-184.)); +#1121=CARTESIAN_POINT('',(-12.1,9.1848509851177E-15,-177.)); +#1122=CARTESIAN_POINT('',(-9.6,1.0899356503924E-14,-177.)); +#1123=CARTESIAN_POINT('Origin',(-12.1,1.00421037445208E-14,-184.)); +#1124=CARTESIAN_POINT('Origin',(-12.6,-13.5,-184.)); +#1125=CARTESIAN_POINT('',(-9.6,-14.7645,-184.)); +#1126=CARTESIAN_POINT('Origin',(-9.6,-13.5,-184.)); +#1127=CARTESIAN_POINT('',(-12.1,-14.7645,-184.)); +#1128=CARTESIAN_POINT('',(-12.6,-14.7645,-184.)); +#1129=CARTESIAN_POINT('Origin',(-12.1,-13.5,-184.)); +#1130=CARTESIAN_POINT('Origin',(-12.6,13.5,-184.)); +#1131=CARTESIAN_POINT('',(-9.6,12.2355,-184.)); +#1132=CARTESIAN_POINT('Origin',(-9.6,13.5,-184.)); +#1133=CARTESIAN_POINT('',(-12.1,12.2355,-184.)); +#1134=CARTESIAN_POINT('',(-12.6,12.2355,-184.)); +#1135=CARTESIAN_POINT('Origin',(-12.1,13.5,-184.)); +#1136=CARTESIAN_POINT('Origin',(-12.6,1.90819582357449E-16,-197.5)); +#1137=CARTESIAN_POINT('',(-9.59999999999999,-1.2645,-197.5)); +#1138=CARTESIAN_POINT('Origin',(-9.59999999999999,1.90819582357449E-16, +-197.5)); +#1139=CARTESIAN_POINT('',(-12.1,-1.2645,-197.5)); +#1140=CARTESIAN_POINT('',(-12.6,-1.2645,-197.5)); +#1141=CARTESIAN_POINT('Origin',(-12.1,1.90819582357449E-16,-197.5)); +#1142=CARTESIAN_POINT('Origin',(-12.6,4.487729632352E-14,-170.5)); +#1143=CARTESIAN_POINT('',(-9.6,-1.26449999999996,-170.5)); +#1144=CARTESIAN_POINT('Origin',(-9.6,4.487729632352E-14,-170.5)); +#1145=CARTESIAN_POINT('',(-12.1,-1.26449999999996,-170.5)); +#1146=CARTESIAN_POINT('',(-12.6,-1.26449999999996,-170.5)); +#1147=CARTESIAN_POINT('Origin',(-12.1,4.487729632352E-14,-170.5)); +#1148=CARTESIAN_POINT('Origin',(2.5,2.25335011043113E-14,-184.)); +#1149=CARTESIAN_POINT('',(-9.6,-17.5,-184.)); +#1150=CARTESIAN_POINT('',(-9.6,17.5,-184.00000049204)); +#1151=CARTESIAN_POINT('Origin',(-9.59999999999999,2.25335011043113E-14, +-184.)); +#1152=CARTESIAN_POINT('',(-12.1,-17.5,-184.)); +#1153=CARTESIAN_POINT('',(2.5,-17.5,-184.)); +#1154=CARTESIAN_POINT('',(-12.1,17.5,-184.00000049204)); +#1155=CARTESIAN_POINT('Origin',(-12.1,2.25335011043113E-14,-184.)); +#1156=CARTESIAN_POINT('',(2.5,17.5,-184.00000049204)); +#1157=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,12.5)); +#1158=CARTESIAN_POINT('',(2.5,-18.6195461813654,10.75)); +#1159=CARTESIAN_POINT('',(2.5,-24.6817240078565,14.25)); +#1160=CARTESIAN_POINT('Origin',(2.5,-21.650635094611,12.5)); +#1161=CARTESIAN_POINT('',(0.,-18.6195461813654,10.75)); +#1162=CARTESIAN_POINT('',(2.5,-18.6195461813654,10.75)); +#1163=CARTESIAN_POINT('',(0.,-24.6817240078565,14.25)); +#1164=CARTESIAN_POINT('Origin',(0.,-21.650635094611,12.5)); +#1165=CARTESIAN_POINT('',(2.5,-24.6817240078565,14.25)); +#1166=CARTESIAN_POINT('Origin',(2.5,-17.5,-55.1544826719044)); +#1167=CARTESIAN_POINT('',(-9.60000000000005,-17.5,-55.1544826719044)); +#1168=CARTESIAN_POINT('',(-9.60000000000002,-17.5,-128.327241335952)); +#1169=CARTESIAN_POINT('',(-12.1,-17.5,-55.1544826719044)); +#1170=CARTESIAN_POINT('',(2.5,-17.5,-55.1544826719044)); +#1171=CARTESIAN_POINT('',(-12.1,-17.5,-128.327241335952)); +#1172=CARTESIAN_POINT('Origin',(2.5,-27.8871550495152,-5.87848477452304)); +#1173=CARTESIAN_POINT('',(-9.58660254037848,-17.5105397713824,-55.1044826719043)); +#1174=CARTESIAN_POINT('Origin',(-9.50000000000005,-17.5,-55.1544826719044)); +#1175=CARTESIAN_POINT('',(2.15166604983954,-21.7962801258198,-34.7732050807569)); +#1176=CARTESIAN_POINT('',(1.70588131360759,-21.6335203781809,-35.5453268931493)); +#1177=CARTESIAN_POINT('',(2.5,-22.070314181761,-33.4732050807569)); +#1178=CARTESIAN_POINT('Origin',(-0.1,-22.070314181761,-33.4732050807569)); +#1179=CARTESIAN_POINT('',(2.5,-27.8871550495152,-5.87848477452304)); +#1180=CARTESIAN_POINT('',(2.5,-27.8871550495152,-5.87848477452303)); +#1181=CARTESIAN_POINT('',(0.,-27.8871550495152,-5.87848477452304)); +#1182=CARTESIAN_POINT('',(2.5,-27.8871550495152,-5.87848477452304)); +#1183=CARTESIAN_POINT('',(0.,-22.070314181761,-33.4732050807569)); +#1184=CARTESIAN_POINT('',(0.,-27.8871550495152,-5.87848477452303)); +#1185=CARTESIAN_POINT('',(-0.0133974596215562,-22.0597744103787,-33.5232050807569)); +#1186=CARTESIAN_POINT('Origin',(-0.1,-22.070314181761,-33.4732050807569)); +#1187=CARTESIAN_POINT('',(-11.7516660498396,-17.7740340559412,-53.8544826719043)); +#1188=CARTESIAN_POINT('',(-0.482457515308155,-21.8885166483109,-34.3356409290072)); +#1189=CARTESIAN_POINT('Origin',(-9.50000000000005,-17.5,-55.1544826719044)); +#1190=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1191=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1192=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1193=CARTESIAN_POINT('Origin',(2.5,17.5,-55.1544826719044)); +#1194=CARTESIAN_POINT('',(-11.7516660498396,17.7740340559412,-53.8544826719043)); +#1195=CARTESIAN_POINT('',(-12.1,17.5,-55.1544826719044)); +#1196=CARTESIAN_POINT('Origin',(-9.50000000000005,17.5,-55.1544826719044)); +#1197=CARTESIAN_POINT('',(-0.0133974596215562,22.0597744103787,-33.5232050807569)); +#1198=CARTESIAN_POINT('',(-11.2657154685492,17.95145869063,-53.0127915751418)); +#1199=CARTESIAN_POINT('',(0.,22.070314181761,-33.4732050807569)); +#1200=CARTESIAN_POINT('Origin',(-0.1,22.070314181761,-33.4732050807569)); +#1201=CARTESIAN_POINT('',(0.,27.8871550495152,-5.87848477452304)); +#1202=CARTESIAN_POINT('',(0.,22.6935775247576,-30.5164837232137)); +#1203=CARTESIAN_POINT('',(2.5,27.8871550495152,-5.87848477452304)); +#1204=CARTESIAN_POINT('',(2.5,27.8871550495152,-5.87848477452304)); +#1205=CARTESIAN_POINT('',(2.5,22.070314181761,-33.4732050807569)); +#1206=CARTESIAN_POINT('',(2.5,22.6935775247576,-30.5164837232137)); +#1207=CARTESIAN_POINT('',(2.15166604983954,21.7962801258198,-34.7732050807569)); +#1208=CARTESIAN_POINT('Origin',(-0.1,22.070314181761,-33.4732050807569)); +#1209=CARTESIAN_POINT('',(-9.58660254037848,17.5105397713824,-55.1044826719043)); +#1210=CARTESIAN_POINT('',(-9.07737663963344,17.6964624205,-54.2224775392839)); +#1211=CARTESIAN_POINT('',(-9.60000000000005,17.5,-55.1544826719044)); +#1212=CARTESIAN_POINT('Origin',(-9.50000000000005,17.5,-55.1544826719044)); +#1213=CARTESIAN_POINT('',(2.5,17.5,-55.1544826719044)); +#1214=CARTESIAN_POINT('Origin',(2.5,17.5,-184.00000049204)); +#1215=CARTESIAN_POINT('',(-12.1,17.5,-192.75000024602)); +#1216=CARTESIAN_POINT('',(-9.59999999999999,17.5,-192.75000024602)); +#1217=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1218=CARTESIAN_POINT('',(2.5,18.6195461813655,10.75)); +#1219=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1220=CARTESIAN_POINT('',(0.,18.6195461813655,10.75)); +#1221=CARTESIAN_POINT('',(2.5,18.6195461813655,10.75)); +#1222=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1223=CARTESIAN_POINT('Origin',(2.5,21.650635094611,12.5)); +#1224=CARTESIAN_POINT('',(2.5,24.6817240078565,14.25)); +#1225=CARTESIAN_POINT('Origin',(2.5,21.650635094611,12.5)); +#1226=CARTESIAN_POINT('',(0.,24.6817240078565,14.25)); +#1227=CARTESIAN_POINT('',(2.5,24.6817240078565,14.25)); +#1228=CARTESIAN_POINT('Origin',(0.,21.650635094611,12.5)); +#1229=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1230=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1231=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1232=CARTESIAN_POINT('Origin',(-9.59999999999999,0.,-201.5)); +#1233=CARTESIAN_POINT('',(-9.60000000000005,0.,-55.1544826719044)); +#1234=CARTESIAN_POINT('Origin',(-12.1,0.,-201.5)); +#1235=CARTESIAN_POINT('',(-12.1,0.,-55.1544826719044)); +#1236=CARTESIAN_POINT('Origin',(-9.50000000000005,0.,-55.1544826719044)); +#1237=CARTESIAN_POINT('',(-9.58660254037848,0.,-55.1044826719043)); +#1238=CARTESIAN_POINT('Origin',(-9.93493649053892,0.,-55.7078147715834)); +#1239=CARTESIAN_POINT('',(2.15166604983954,0.,-34.7732050807569)); +#1240=CARTESIAN_POINT('Origin',(-0.1,0.,-33.4732050807569)); +#1241=CARTESIAN_POINT('',(2.5,0.,-33.4732050807569)); +#1242=CARTESIAN_POINT('Origin',(2.5,0.,0.)); +#1243=CARTESIAN_POINT('Origin',(-9.50000000000005,0.,-55.1544826719044)); +#1244=CARTESIAN_POINT('',(-11.7516660498396,0.,-53.8544826719043)); +#1245=CARTESIAN_POINT('Origin',(-12.1,0.,-54.4578147715834)); +#1246=CARTESIAN_POINT('',(-0.0133974596215562,0.,-33.5232050807569)); +#1247=CARTESIAN_POINT('Origin',(-0.1,0.,-33.4732050807569)); +#1248=CARTESIAN_POINT('',(0.,0.,-33.4732050807569)); +#1249=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#1250=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1254, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1251=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1254, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1252=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1250)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1254,#1256,#1257)) +REPRESENTATION_CONTEXT('','3D') +); +#1253=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1251)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1254,#1256,#1257)) +REPRESENTATION_CONTEXT('','3D') +); +#1254=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#1255=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT($,.METRE.) +); +#1256=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#1257=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#1258=SHAPE_DEFINITION_REPRESENTATION(#1259,#1260); +#1259=PRODUCT_DEFINITION_SHAPE('',$,#1262); +#1260=SHAPE_REPRESENTATION('',(#738),#1252); +#1261=PRODUCT_DEFINITION_CONTEXT('part definition',#1266,'design'); +#1262=PRODUCT_DEFINITION('link3-4-2','link3-4-2 v3',#1263,#1261); +#1263=PRODUCT_DEFINITION_FORMATION('',$,#1268); +#1264=PRODUCT_RELATED_PRODUCT_CATEGORY('link3-4-2 v3','link3-4-2 v3',(#1268)); +#1265=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#1266); +#1266=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#1267=PRODUCT_CONTEXT('part definition',#1266,'mechanical'); +#1268=PRODUCT('link3-4-2','link3-4-2 v3',$,(#1267)); +#1269=PRESENTATION_STYLE_ASSIGNMENT((#1271)); +#1270=PRESENTATION_STYLE_ASSIGNMENT((#1272)); +#1271=SURFACE_STYLE_USAGE(.BOTH.,#1273); +#1272=SURFACE_STYLE_USAGE(.BOTH.,#1274); +#1273=SURFACE_SIDE_STYLE('',(#1275)); +#1274=SURFACE_SIDE_STYLE('',(#1276)); +#1275=SURFACE_STYLE_FILL_AREA(#1277); +#1276=SURFACE_STYLE_FILL_AREA(#1278); +#1277=FILL_AREA_STYLE('Steel - Satin',(#1279)); +#1278=FILL_AREA_STYLE('Aluminum - Satin',(#1280)); +#1279=FILL_AREA_STYLE_COLOUR('Steel - Satin',#1281); +#1280=FILL_AREA_STYLE_COLOUR('Aluminum - Satin',#1282); +#1281=COLOUR_RGB('Steel - Satin',0.627450980392157,0.627450980392157,0.627450980392157); +#1282=COLOUR_RGB('Aluminum - Satin',0.96078431372549,0.96078431372549,0.964705882352941); +ENDSEC; +END-ISO-10303-21; diff --git a/hardware/follower_STEPs/link4-5_v0.2.0.step b/hardware/follower_STEPs/link4-5_v0.2.0.step new file mode 100644 index 0000000000000000000000000000000000000000..b646cdad8771c444edd744403cd329a30496eea6 --- /dev/null +++ b/hardware/follower_STEPs/link4-5_v0.2.0.step @@ -0,0 +1,1618 @@ +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 */ 'link4-5_v0.2.0.step', +/* time_stamp */ '2025-10-08T20:57:13+02:00', +/* author */ (''), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v20.1', +/* originating_system */ 'Autodesk Translation Framework v14.17.0.0', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#1534); +#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#1541,#12); +#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#1533); +#13=STYLED_ITEM('',(#1550),#14); +#14=MANIFOLD_SOLID_BREP('Body2',#894); +#15=FACE_BOUND('',#140,.T.); +#16=FACE_BOUND('',#141,.T.); +#17=FACE_BOUND('',#142,.T.); +#18=FACE_BOUND('',#143,.T.); +#19=FACE_BOUND('',#144,.T.); +#20=FACE_BOUND('',#145,.T.); +#21=FACE_BOUND('',#146,.T.); +#22=FACE_BOUND('',#149,.T.); +#23=FACE_BOUND('',#150,.T.); +#24=FACE_BOUND('',#151,.T.); +#25=FACE_BOUND('',#152,.T.); +#26=FACE_BOUND('',#153,.T.); +#27=FACE_BOUND('',#156,.T.); +#28=FACE_BOUND('',#157,.T.); +#29=FACE_BOUND('',#158,.T.); +#30=FACE_BOUND('',#159,.T.); +#31=FACE_BOUND('',#160,.T.); +#32=FACE_BOUND('',#161,.T.); +#33=FACE_BOUND('',#162,.T.); +#34=FACE_BOUND('',#173,.T.); +#35=FACE_BOUND('',#174,.T.); +#36=FACE_BOUND('',#175,.T.); +#37=FACE_BOUND('',#176,.T.); +#38=FACE_BOUND('',#177,.T.); +#39=FACE_BOUND('',#178,.T.); +#40=FACE_BOUND('',#179,.T.); +#41=FACE_BOUND('',#182,.T.); +#42=FACE_BOUND('',#183,.T.); +#43=FACE_BOUND('',#184,.T.); +#44=FACE_BOUND('',#185,.T.); +#45=FACE_BOUND('',#186,.T.); +#46=FACE_BOUND('',#189,.T.); +#47=FACE_BOUND('',#190,.T.); +#48=FACE_BOUND('',#191,.T.); +#49=FACE_BOUND('',#192,.T.); +#50=FACE_BOUND('',#193,.T.); +#51=FACE_BOUND('',#194,.T.); +#52=FACE_BOUND('',#195,.T.); +#53=PLANE('',#965); +#54=PLANE('',#970); +#55=PLANE('',#971); +#56=PLANE('',#978); +#57=PLANE('',#979); +#58=PLANE('',#980); +#59=PLANE('',#983); +#60=PLANE('',#991); +#61=PLANE('',#992); +#62=PLANE('',#994); +#63=PLANE('',#996); +#64=PLANE('',#1007); +#65=PLANE('',#1008); +#66=PLANE('',#1010); +#67=PLANE('',#1012); +#68=FACE_OUTER_BOUND('',#113,.T.); +#69=FACE_OUTER_BOUND('',#114,.T.); +#70=FACE_OUTER_BOUND('',#115,.T.); +#71=FACE_OUTER_BOUND('',#116,.T.); +#72=FACE_OUTER_BOUND('',#117,.T.); +#73=FACE_OUTER_BOUND('',#118,.T.); +#74=FACE_OUTER_BOUND('',#119,.T.); +#75=FACE_OUTER_BOUND('',#120,.T.); +#76=FACE_OUTER_BOUND('',#121,.T.); +#77=FACE_OUTER_BOUND('',#122,.T.); +#78=FACE_OUTER_BOUND('',#123,.T.); +#79=FACE_OUTER_BOUND('',#124,.T.); +#80=FACE_OUTER_BOUND('',#125,.T.); +#81=FACE_OUTER_BOUND('',#126,.T.); +#82=FACE_OUTER_BOUND('',#127,.T.); +#83=FACE_OUTER_BOUND('',#128,.T.); +#84=FACE_OUTER_BOUND('',#129,.T.); +#85=FACE_OUTER_BOUND('',#130,.T.); +#86=FACE_OUTER_BOUND('',#131,.T.); +#87=FACE_OUTER_BOUND('',#132,.T.); +#88=FACE_OUTER_BOUND('',#133,.T.); +#89=FACE_OUTER_BOUND('',#134,.T.); +#90=FACE_OUTER_BOUND('',#135,.T.); +#91=FACE_OUTER_BOUND('',#136,.T.); +#92=FACE_OUTER_BOUND('',#137,.T.); +#93=FACE_OUTER_BOUND('',#138,.T.); +#94=FACE_OUTER_BOUND('',#139,.T.); +#95=FACE_OUTER_BOUND('',#147,.T.); +#96=FACE_OUTER_BOUND('',#148,.T.); +#97=FACE_OUTER_BOUND('',#154,.T.); +#98=FACE_OUTER_BOUND('',#155,.T.); +#99=FACE_OUTER_BOUND('',#163,.T.); +#100=FACE_OUTER_BOUND('',#164,.T.); +#101=FACE_OUTER_BOUND('',#165,.T.); +#102=FACE_OUTER_BOUND('',#166,.T.); +#103=FACE_OUTER_BOUND('',#167,.T.); +#104=FACE_OUTER_BOUND('',#168,.T.); +#105=FACE_OUTER_BOUND('',#169,.T.); +#106=FACE_OUTER_BOUND('',#170,.T.); +#107=FACE_OUTER_BOUND('',#171,.T.); +#108=FACE_OUTER_BOUND('',#172,.T.); +#109=FACE_OUTER_BOUND('',#180,.T.); +#110=FACE_OUTER_BOUND('',#181,.T.); +#111=FACE_OUTER_BOUND('',#187,.T.); +#112=FACE_OUTER_BOUND('',#188,.T.); +#113=EDGE_LOOP('',(#577,#578,#579,#580)); +#114=EDGE_LOOP('',(#581,#582,#583,#584)); +#115=EDGE_LOOP('',(#585,#586,#587,#588)); +#116=EDGE_LOOP('',(#589,#590,#591,#592)); +#117=EDGE_LOOP('',(#593,#594,#595,#596)); +#118=EDGE_LOOP('',(#597,#598,#599,#600)); +#119=EDGE_LOOP('',(#601,#602,#603,#604)); +#120=EDGE_LOOP('',(#605,#606,#607,#608)); +#121=EDGE_LOOP('',(#609,#610,#611,#612)); +#122=EDGE_LOOP('',(#613,#614,#615,#616)); +#123=EDGE_LOOP('',(#617,#618,#619,#620)); +#124=EDGE_LOOP('',(#621,#622,#623,#624)); +#125=EDGE_LOOP('',(#625,#626,#627,#628)); +#126=EDGE_LOOP('',(#629,#630,#631,#632)); +#127=EDGE_LOOP('',(#633,#634,#635,#636)); +#128=EDGE_LOOP('',(#637,#638,#639,#640)); +#129=EDGE_LOOP('',(#641,#642,#643,#644)); +#130=EDGE_LOOP('',(#645,#646,#647,#648)); +#131=EDGE_LOOP('',(#649,#650,#651,#652)); +#132=EDGE_LOOP('',(#653,#654,#655,#656,#657,#658,#659,#660)); +#133=EDGE_LOOP('',(#661,#662,#663,#664)); +#134=EDGE_LOOP('',(#665,#666,#667,#668)); +#135=EDGE_LOOP('',(#669,#670,#671,#672)); +#136=EDGE_LOOP('',(#673,#674,#675,#676)); +#137=EDGE_LOOP('',(#677,#678,#679,#680)); +#138=EDGE_LOOP('',(#681,#682,#683,#684)); +#139=EDGE_LOOP('',(#685,#686,#687,#688)); +#140=EDGE_LOOP('',(#689)); +#141=EDGE_LOOP('',(#690)); +#142=EDGE_LOOP('',(#691)); +#143=EDGE_LOOP('',(#692)); +#144=EDGE_LOOP('',(#693)); +#145=EDGE_LOOP('',(#694)); +#146=EDGE_LOOP('',(#695)); +#147=EDGE_LOOP('',(#696,#697,#698,#699)); +#148=EDGE_LOOP('',(#700,#701,#702,#703,#704,#705,#706,#707,#708,#709,#710, +#711)); +#149=EDGE_LOOP('',(#712)); +#150=EDGE_LOOP('',(#713)); +#151=EDGE_LOOP('',(#714)); +#152=EDGE_LOOP('',(#715)); +#153=EDGE_LOOP('',(#716)); +#154=EDGE_LOOP('',(#717,#718,#719,#720)); +#155=EDGE_LOOP('',(#721,#722,#723,#724)); +#156=EDGE_LOOP('',(#725)); +#157=EDGE_LOOP('',(#726)); +#158=EDGE_LOOP('',(#727)); +#159=EDGE_LOOP('',(#728)); +#160=EDGE_LOOP('',(#729)); +#161=EDGE_LOOP('',(#730)); +#162=EDGE_LOOP('',(#731)); +#163=EDGE_LOOP('',(#732,#733,#734,#735,#736,#737)); +#164=EDGE_LOOP('',(#738,#739,#740,#741,#742,#743)); +#165=EDGE_LOOP('',(#744,#745,#746,#747)); +#166=EDGE_LOOP('',(#748,#749,#750,#751)); +#167=EDGE_LOOP('',(#752,#753,#754,#755)); +#168=EDGE_LOOP('',(#756,#757,#758,#759)); +#169=EDGE_LOOP('',(#760,#761,#762,#763)); +#170=EDGE_LOOP('',(#764,#765,#766,#767)); +#171=EDGE_LOOP('',(#768,#769,#770,#771)); +#172=EDGE_LOOP('',(#772,#773,#774,#775)); +#173=EDGE_LOOP('',(#776)); +#174=EDGE_LOOP('',(#777)); +#175=EDGE_LOOP('',(#778)); +#176=EDGE_LOOP('',(#779)); +#177=EDGE_LOOP('',(#780)); +#178=EDGE_LOOP('',(#781)); +#179=EDGE_LOOP('',(#782)); +#180=EDGE_LOOP('',(#783,#784,#785,#786)); +#181=EDGE_LOOP('',(#787,#788,#789,#790,#791,#792,#793,#794,#795,#796,#797, +#798)); +#182=EDGE_LOOP('',(#799)); +#183=EDGE_LOOP('',(#800)); +#184=EDGE_LOOP('',(#801)); +#185=EDGE_LOOP('',(#802)); +#186=EDGE_LOOP('',(#803)); +#187=EDGE_LOOP('',(#804,#805,#806,#807)); +#188=EDGE_LOOP('',(#808,#809,#810,#811)); +#189=EDGE_LOOP('',(#812)); +#190=EDGE_LOOP('',(#813)); +#191=EDGE_LOOP('',(#814)); +#192=EDGE_LOOP('',(#815)); +#193=EDGE_LOOP('',(#816)); +#194=EDGE_LOOP('',(#817)); +#195=EDGE_LOOP('',(#818)); +#196=LINE('',#1291,#257); +#197=LINE('',#1297,#258); +#198=LINE('',#1303,#259); +#199=LINE('',#1309,#260); +#200=LINE('',#1315,#261); +#201=LINE('',#1321,#262); +#202=LINE('',#1327,#263); +#203=LINE('',#1333,#264); +#204=LINE('',#1339,#265); +#205=LINE('',#1345,#266); +#206=LINE('',#1351,#267); +#207=LINE('',#1357,#268); +#208=LINE('',#1363,#269); +#209=LINE('',#1369,#270); +#210=LINE('',#1375,#271); +#211=LINE('',#1381,#272); +#212=LINE('',#1387,#273); +#213=LINE('',#1393,#274); +#214=LINE('',#1399,#275); +#215=LINE('',#1406,#276); +#216=LINE('',#1410,#277); +#217=LINE('',#1414,#278); +#218=LINE('',#1417,#279); +#219=LINE('',#1420,#280); +#220=LINE('',#1422,#281); +#221=LINE('',#1423,#282); +#222=LINE('',#1426,#283); +#223=LINE('',#1428,#284); +#224=LINE('',#1429,#285); +#225=LINE('',#1435,#286); +#226=LINE('',#1440,#287); +#227=LINE('',#1444,#288); +#228=LINE('',#1446,#289); +#229=LINE('',#1447,#290); +#230=LINE('',#1450,#291); +#231=LINE('',#1452,#292); +#232=LINE('',#1453,#293); +#233=LINE('',#1455,#294); +#234=LINE('',#1458,#295); +#235=LINE('',#1462,#296); +#236=LINE('',#1464,#297); +#237=LINE('',#1466,#298); +#238=LINE('',#1478,#299); +#239=LINE('',#1479,#300); +#240=LINE('',#1481,#301); +#241=LINE('',#1488,#302); +#242=LINE('',#1489,#303); +#243=LINE('',#1492,#304); +#244=LINE('',#1494,#305); +#245=LINE('',#1498,#306); +#246=LINE('',#1499,#307); +#247=LINE('',#1503,#308); +#248=LINE('',#1507,#309); +#249=LINE('',#1511,#310); +#250=LINE('',#1515,#311); +#251=LINE('',#1519,#312); +#252=LINE('',#1521,#313); +#253=LINE('',#1523,#314); +#254=LINE('',#1525,#315); +#255=LINE('',#1527,#316); +#256=LINE('',#1529,#317); +#257=VECTOR('',#1019,7.); +#258=VECTOR('',#1026,7.); +#259=VECTOR('',#1033,1.6); +#260=VECTOR('',#1040,1.6); +#261=VECTOR('',#1047,1.6); +#262=VECTOR('',#1054,1.6); +#263=VECTOR('',#1061,1.6); +#264=VECTOR('',#1068,1.6); +#265=VECTOR('',#1075,1.6); +#266=VECTOR('',#1082,1.6); +#267=VECTOR('',#1089,1.6); +#268=VECTOR('',#1096,1.6); +#269=VECTOR('',#1103,1.6); +#270=VECTOR('',#1110,1.6); +#271=VECTOR('',#1117,1.6); +#272=VECTOR('',#1124,1.6); +#273=VECTOR('',#1131,1.6); +#274=VECTOR('',#1138,1.6); +#275=VECTOR('',#1145,1.6); +#276=VECTOR('',#1152,10.); +#277=VECTOR('',#1155,10.); +#278=VECTOR('',#1158,10.); +#279=VECTOR('',#1161,10.); +#280=VECTOR('',#1164,10.); +#281=VECTOR('',#1165,10.); +#282=VECTOR('',#1166,10.); +#283=VECTOR('',#1169,10.); +#284=VECTOR('',#1170,10.); +#285=VECTOR('',#1171,10.); +#286=VECTOR('',#1178,10.); +#287=VECTOR('',#1183,10.); +#288=VECTOR('',#1188,10.); +#289=VECTOR('',#1189,10.); +#290=VECTOR('',#1190,10.); +#291=VECTOR('',#1193,10.); +#292=VECTOR('',#1194,10.); +#293=VECTOR('',#1195,10.); +#294=VECTOR('',#1198,10.); +#295=VECTOR('',#1201,10.); +#296=VECTOR('',#1206,10.); +#297=VECTOR('',#1207,10.); +#298=VECTOR('',#1208,10.); +#299=VECTOR('',#1219,10.); +#300=VECTOR('',#1220,10.); +#301=VECTOR('',#1223,10.); +#302=VECTOR('',#1232,10.); +#303=VECTOR('',#1233,10.); +#304=VECTOR('',#1236,10.); +#305=VECTOR('',#1237,10.); +#306=VECTOR('',#1242,10.); +#307=VECTOR('',#1243,10.); +#308=VECTOR('',#1248,10.); +#309=VECTOR('',#1253,10.); +#310=VECTOR('',#1258,10.); +#311=VECTOR('',#1263,10.); +#312=VECTOR('',#1268,10.); +#313=VECTOR('',#1271,10.); +#314=VECTOR('',#1274,10.); +#315=VECTOR('',#1277,10.); +#316=VECTOR('',#1280,10.); +#317=VECTOR('',#1283,10.); +#318=CIRCLE('',#909,7.); +#319=CIRCLE('',#910,7.); +#320=CIRCLE('',#912,7.); +#321=CIRCLE('',#913,7.); +#322=CIRCLE('',#915,1.6); +#323=CIRCLE('',#916,1.6); +#324=CIRCLE('',#918,1.6); +#325=CIRCLE('',#919,1.6); +#326=CIRCLE('',#921,1.6); +#327=CIRCLE('',#922,1.6); +#328=CIRCLE('',#924,1.6); +#329=CIRCLE('',#925,1.6); +#330=CIRCLE('',#927,1.6); +#331=CIRCLE('',#928,1.6); +#332=CIRCLE('',#930,1.6); +#333=CIRCLE('',#931,1.6); +#334=CIRCLE('',#933,1.6); +#335=CIRCLE('',#934,1.6); +#336=CIRCLE('',#936,1.6); +#337=CIRCLE('',#937,1.6); +#338=CIRCLE('',#939,1.6); +#339=CIRCLE('',#940,1.6); +#340=CIRCLE('',#942,1.6); +#341=CIRCLE('',#943,1.6); +#342=CIRCLE('',#945,1.6); +#343=CIRCLE('',#946,1.6); +#344=CIRCLE('',#948,1.6); +#345=CIRCLE('',#949,1.6); +#346=CIRCLE('',#951,1.6); +#347=CIRCLE('',#952,1.6); +#348=CIRCLE('',#954,1.6); +#349=CIRCLE('',#955,1.6); +#350=CIRCLE('',#957,1.6); +#351=CIRCLE('',#958,1.6); +#352=CIRCLE('',#960,1.6); +#353=CIRCLE('',#961,1.6); +#354=CIRCLE('',#963,1.6); +#355=CIRCLE('',#964,1.6); +#356=CIRCLE('',#966,0.5); +#357=CIRCLE('',#967,3.); +#358=CIRCLE('',#968,3.); +#359=CIRCLE('',#969,0.5); +#360=CIRCLE('',#973,17.5); +#361=CIRCLE('',#974,17.5); +#362=CIRCLE('',#976,17.5); +#363=CIRCLE('',#977,17.5); +#364=CIRCLE('',#982,0.5); +#365=CIRCLE('',#984,28.5); +#366=CIRCLE('',#985,3.49999999999998); +#367=CIRCLE('',#986,21.5); +#368=CIRCLE('',#987,3.49999999999998); +#369=CIRCLE('',#988,28.5); +#370=CIRCLE('',#990,0.5); +#371=CIRCLE('',#993,3.); +#372=CIRCLE('',#995,3.); +#373=CIRCLE('',#998,28.5); +#374=CIRCLE('',#1000,3.49999999999998); +#375=CIRCLE('',#1002,21.5); +#376=CIRCLE('',#1004,3.49999999999998); +#377=CIRCLE('',#1006,28.5); +#378=VERTEX_POINT('',#1288); +#379=VERTEX_POINT('',#1290); +#380=VERTEX_POINT('',#1294); +#381=VERTEX_POINT('',#1296); +#382=VERTEX_POINT('',#1300); +#383=VERTEX_POINT('',#1302); +#384=VERTEX_POINT('',#1306); +#385=VERTEX_POINT('',#1308); +#386=VERTEX_POINT('',#1312); +#387=VERTEX_POINT('',#1314); +#388=VERTEX_POINT('',#1318); +#389=VERTEX_POINT('',#1320); +#390=VERTEX_POINT('',#1324); +#391=VERTEX_POINT('',#1326); +#392=VERTEX_POINT('',#1330); +#393=VERTEX_POINT('',#1332); +#394=VERTEX_POINT('',#1336); +#395=VERTEX_POINT('',#1338); +#396=VERTEX_POINT('',#1342); +#397=VERTEX_POINT('',#1344); +#398=VERTEX_POINT('',#1348); +#399=VERTEX_POINT('',#1350); +#400=VERTEX_POINT('',#1354); +#401=VERTEX_POINT('',#1356); +#402=VERTEX_POINT('',#1360); +#403=VERTEX_POINT('',#1362); +#404=VERTEX_POINT('',#1366); +#405=VERTEX_POINT('',#1368); +#406=VERTEX_POINT('',#1372); +#407=VERTEX_POINT('',#1374); +#408=VERTEX_POINT('',#1378); +#409=VERTEX_POINT('',#1380); +#410=VERTEX_POINT('',#1384); +#411=VERTEX_POINT('',#1386); +#412=VERTEX_POINT('',#1390); +#413=VERTEX_POINT('',#1392); +#414=VERTEX_POINT('',#1396); +#415=VERTEX_POINT('',#1398); +#416=VERTEX_POINT('',#1402); +#417=VERTEX_POINT('',#1403); +#418=VERTEX_POINT('',#1405); +#419=VERTEX_POINT('',#1407); +#420=VERTEX_POINT('',#1409); +#421=VERTEX_POINT('',#1411); +#422=VERTEX_POINT('',#1413); +#423=VERTEX_POINT('',#1415); +#424=VERTEX_POINT('',#1419); +#425=VERTEX_POINT('',#1421); +#426=VERTEX_POINT('',#1425); +#427=VERTEX_POINT('',#1427); +#428=VERTEX_POINT('',#1431); +#429=VERTEX_POINT('',#1433); +#430=VERTEX_POINT('',#1437); +#431=VERTEX_POINT('',#1439); +#432=VERTEX_POINT('',#1443); +#433=VERTEX_POINT('',#1445); +#434=VERTEX_POINT('',#1449); +#435=VERTEX_POINT('',#1451); +#436=VERTEX_POINT('',#1457); +#437=VERTEX_POINT('',#1461); +#438=VERTEX_POINT('',#1463); +#439=VERTEX_POINT('',#1465); +#440=VERTEX_POINT('',#1467); +#441=VERTEX_POINT('',#1469); +#442=VERTEX_POINT('',#1471); +#443=VERTEX_POINT('',#1473); +#444=VERTEX_POINT('',#1475); +#445=VERTEX_POINT('',#1477); +#446=VERTEX_POINT('',#1485); +#447=VERTEX_POINT('',#1487); +#448=VERTEX_POINT('',#1491); +#449=VERTEX_POINT('',#1493); +#450=VERTEX_POINT('',#1497); +#451=VERTEX_POINT('',#1501); +#452=VERTEX_POINT('',#1505); +#453=VERTEX_POINT('',#1509); +#454=VERTEX_POINT('',#1513); +#455=VERTEX_POINT('',#1517); +#456=EDGE_CURVE('',#378,#378,#318,.T.); +#457=EDGE_CURVE('',#378,#379,#196,.T.); +#458=EDGE_CURVE('',#379,#379,#319,.T.); +#459=EDGE_CURVE('',#380,#380,#320,.T.); +#460=EDGE_CURVE('',#380,#381,#197,.T.); +#461=EDGE_CURVE('',#381,#381,#321,.T.); +#462=EDGE_CURVE('',#382,#382,#322,.T.); +#463=EDGE_CURVE('',#382,#383,#198,.T.); +#464=EDGE_CURVE('',#383,#383,#323,.T.); +#465=EDGE_CURVE('',#384,#384,#324,.T.); +#466=EDGE_CURVE('',#384,#385,#199,.T.); +#467=EDGE_CURVE('',#385,#385,#325,.T.); +#468=EDGE_CURVE('',#386,#386,#326,.T.); +#469=EDGE_CURVE('',#386,#387,#200,.T.); +#470=EDGE_CURVE('',#387,#387,#327,.T.); +#471=EDGE_CURVE('',#388,#388,#328,.T.); +#472=EDGE_CURVE('',#388,#389,#201,.T.); +#473=EDGE_CURVE('',#389,#389,#329,.T.); +#474=EDGE_CURVE('',#390,#390,#330,.T.); +#475=EDGE_CURVE('',#390,#391,#202,.T.); +#476=EDGE_CURVE('',#391,#391,#331,.T.); +#477=EDGE_CURVE('',#392,#392,#332,.T.); +#478=EDGE_CURVE('',#392,#393,#203,.T.); +#479=EDGE_CURVE('',#393,#393,#333,.T.); +#480=EDGE_CURVE('',#394,#394,#334,.T.); +#481=EDGE_CURVE('',#394,#395,#204,.T.); +#482=EDGE_CURVE('',#395,#395,#335,.T.); +#483=EDGE_CURVE('',#396,#396,#336,.T.); +#484=EDGE_CURVE('',#396,#397,#205,.T.); +#485=EDGE_CURVE('',#397,#397,#337,.T.); +#486=EDGE_CURVE('',#398,#398,#338,.T.); +#487=EDGE_CURVE('',#398,#399,#206,.T.); +#488=EDGE_CURVE('',#399,#399,#339,.T.); +#489=EDGE_CURVE('',#400,#400,#340,.T.); +#490=EDGE_CURVE('',#400,#401,#207,.T.); +#491=EDGE_CURVE('',#401,#401,#341,.T.); +#492=EDGE_CURVE('',#402,#402,#342,.T.); +#493=EDGE_CURVE('',#402,#403,#208,.T.); +#494=EDGE_CURVE('',#403,#403,#343,.T.); +#495=EDGE_CURVE('',#404,#404,#344,.T.); +#496=EDGE_CURVE('',#404,#405,#209,.T.); +#497=EDGE_CURVE('',#405,#405,#345,.T.); +#498=EDGE_CURVE('',#406,#406,#346,.T.); +#499=EDGE_CURVE('',#406,#407,#210,.T.); +#500=EDGE_CURVE('',#407,#407,#347,.T.); +#501=EDGE_CURVE('',#408,#408,#348,.T.); +#502=EDGE_CURVE('',#408,#409,#211,.T.); +#503=EDGE_CURVE('',#409,#409,#349,.T.); +#504=EDGE_CURVE('',#410,#410,#350,.T.); +#505=EDGE_CURVE('',#410,#411,#212,.T.); +#506=EDGE_CURVE('',#411,#411,#351,.T.); +#507=EDGE_CURVE('',#412,#412,#352,.T.); +#508=EDGE_CURVE('',#412,#413,#213,.T.); +#509=EDGE_CURVE('',#413,#413,#353,.T.); +#510=EDGE_CURVE('',#414,#414,#354,.T.); +#511=EDGE_CURVE('',#414,#415,#214,.T.); +#512=EDGE_CURVE('',#415,#415,#355,.T.); +#513=EDGE_CURVE('',#416,#417,#356,.T.); +#514=EDGE_CURVE('',#416,#418,#215,.T.); +#515=EDGE_CURVE('',#419,#418,#357,.T.); +#516=EDGE_CURVE('',#420,#419,#216,.T.); +#517=EDGE_CURVE('',#421,#420,#358,.T.); +#518=EDGE_CURVE('',#421,#422,#217,.T.); +#519=EDGE_CURVE('',#423,#422,#359,.T.); +#520=EDGE_CURVE('',#417,#423,#218,.T.); +#521=EDGE_CURVE('',#422,#424,#219,.T.); +#522=EDGE_CURVE('',#425,#421,#220,.T.); +#523=EDGE_CURVE('',#425,#424,#221,.T.); +#524=EDGE_CURVE('',#426,#416,#222,.T.); +#525=EDGE_CURVE('',#426,#427,#223,.T.); +#526=EDGE_CURVE('',#418,#427,#224,.T.); +#527=EDGE_CURVE('',#424,#428,#360,.T.); +#528=EDGE_CURVE('',#429,#425,#361,.T.); +#529=EDGE_CURVE('',#429,#428,#225,.T.); +#530=EDGE_CURVE('',#430,#426,#362,.T.); +#531=EDGE_CURVE('',#430,#431,#226,.T.); +#532=EDGE_CURVE('',#427,#431,#363,.T.); +#533=EDGE_CURVE('',#428,#432,#227,.T.); +#534=EDGE_CURVE('',#433,#429,#228,.T.); +#535=EDGE_CURVE('',#432,#433,#229,.T.); +#536=EDGE_CURVE('',#434,#430,#230,.T.); +#537=EDGE_CURVE('',#435,#434,#231,.T.); +#538=EDGE_CURVE('',#431,#435,#232,.T.); +#539=EDGE_CURVE('',#416,#434,#233,.T.); +#540=EDGE_CURVE('',#436,#417,#234,.T.); +#541=EDGE_CURVE('',#436,#434,#364,.T.); +#542=EDGE_CURVE('',#423,#437,#235,.T.); +#543=EDGE_CURVE('',#437,#438,#236,.T.); +#544=EDGE_CURVE('',#438,#439,#237,.T.); +#545=EDGE_CURVE('',#439,#440,#365,.T.); +#546=EDGE_CURVE('',#440,#441,#366,.T.); +#547=EDGE_CURVE('',#441,#442,#367,.T.); +#548=EDGE_CURVE('',#442,#443,#368,.T.); +#549=EDGE_CURVE('',#443,#444,#369,.T.); +#550=EDGE_CURVE('',#444,#445,#238,.T.); +#551=EDGE_CURVE('',#445,#436,#239,.T.); +#552=EDGE_CURVE('',#432,#422,#240,.T.); +#553=EDGE_CURVE('',#432,#437,#370,.T.); +#554=EDGE_CURVE('',#446,#433,#371,.T.); +#555=EDGE_CURVE('',#447,#446,#241,.T.); +#556=EDGE_CURVE('',#447,#438,#242,.T.); +#557=EDGE_CURVE('',#448,#445,#243,.T.); +#558=EDGE_CURVE('',#449,#448,#244,.T.); +#559=EDGE_CURVE('',#435,#449,#372,.T.); +#560=EDGE_CURVE('',#450,#447,#245,.T.); +#561=EDGE_CURVE('',#450,#439,#246,.T.); +#562=EDGE_CURVE('',#451,#450,#373,.T.); +#563=EDGE_CURVE('',#451,#440,#247,.T.); +#564=EDGE_CURVE('',#452,#451,#374,.T.); +#565=EDGE_CURVE('',#452,#441,#248,.T.); +#566=EDGE_CURVE('',#453,#452,#375,.T.); +#567=EDGE_CURVE('',#453,#442,#249,.T.); +#568=EDGE_CURVE('',#454,#453,#376,.T.); +#569=EDGE_CURVE('',#454,#443,#250,.T.); +#570=EDGE_CURVE('',#455,#454,#377,.T.); +#571=EDGE_CURVE('',#455,#444,#251,.T.); +#572=EDGE_CURVE('',#448,#455,#252,.T.); +#573=EDGE_CURVE('',#418,#435,#253,.T.); +#574=EDGE_CURVE('',#449,#419,#254,.T.); +#575=EDGE_CURVE('',#420,#446,#255,.T.); +#576=EDGE_CURVE('',#433,#421,#256,.T.); +#577=ORIENTED_EDGE('',*,*,#456,.F.); +#578=ORIENTED_EDGE('',*,*,#457,.T.); +#579=ORIENTED_EDGE('',*,*,#458,.F.); +#580=ORIENTED_EDGE('',*,*,#457,.F.); +#581=ORIENTED_EDGE('',*,*,#459,.F.); +#582=ORIENTED_EDGE('',*,*,#460,.T.); +#583=ORIENTED_EDGE('',*,*,#461,.F.); +#584=ORIENTED_EDGE('',*,*,#460,.F.); +#585=ORIENTED_EDGE('',*,*,#462,.F.); +#586=ORIENTED_EDGE('',*,*,#463,.T.); +#587=ORIENTED_EDGE('',*,*,#464,.F.); +#588=ORIENTED_EDGE('',*,*,#463,.F.); +#589=ORIENTED_EDGE('',*,*,#465,.F.); +#590=ORIENTED_EDGE('',*,*,#466,.T.); +#591=ORIENTED_EDGE('',*,*,#467,.F.); +#592=ORIENTED_EDGE('',*,*,#466,.F.); +#593=ORIENTED_EDGE('',*,*,#468,.F.); +#594=ORIENTED_EDGE('',*,*,#469,.T.); +#595=ORIENTED_EDGE('',*,*,#470,.F.); +#596=ORIENTED_EDGE('',*,*,#469,.F.); +#597=ORIENTED_EDGE('',*,*,#471,.F.); +#598=ORIENTED_EDGE('',*,*,#472,.T.); +#599=ORIENTED_EDGE('',*,*,#473,.F.); +#600=ORIENTED_EDGE('',*,*,#472,.F.); +#601=ORIENTED_EDGE('',*,*,#474,.F.); +#602=ORIENTED_EDGE('',*,*,#475,.T.); +#603=ORIENTED_EDGE('',*,*,#476,.F.); +#604=ORIENTED_EDGE('',*,*,#475,.F.); +#605=ORIENTED_EDGE('',*,*,#477,.F.); +#606=ORIENTED_EDGE('',*,*,#478,.T.); +#607=ORIENTED_EDGE('',*,*,#479,.F.); +#608=ORIENTED_EDGE('',*,*,#478,.F.); +#609=ORIENTED_EDGE('',*,*,#480,.F.); +#610=ORIENTED_EDGE('',*,*,#481,.T.); +#611=ORIENTED_EDGE('',*,*,#482,.F.); +#612=ORIENTED_EDGE('',*,*,#481,.F.); +#613=ORIENTED_EDGE('',*,*,#483,.F.); +#614=ORIENTED_EDGE('',*,*,#484,.T.); +#615=ORIENTED_EDGE('',*,*,#485,.F.); +#616=ORIENTED_EDGE('',*,*,#484,.F.); +#617=ORIENTED_EDGE('',*,*,#486,.F.); +#618=ORIENTED_EDGE('',*,*,#487,.T.); +#619=ORIENTED_EDGE('',*,*,#488,.F.); +#620=ORIENTED_EDGE('',*,*,#487,.F.); +#621=ORIENTED_EDGE('',*,*,#489,.F.); +#622=ORIENTED_EDGE('',*,*,#490,.T.); +#623=ORIENTED_EDGE('',*,*,#491,.F.); +#624=ORIENTED_EDGE('',*,*,#490,.F.); +#625=ORIENTED_EDGE('',*,*,#492,.F.); +#626=ORIENTED_EDGE('',*,*,#493,.T.); +#627=ORIENTED_EDGE('',*,*,#494,.F.); +#628=ORIENTED_EDGE('',*,*,#493,.F.); +#629=ORIENTED_EDGE('',*,*,#495,.F.); +#630=ORIENTED_EDGE('',*,*,#496,.T.); +#631=ORIENTED_EDGE('',*,*,#497,.F.); +#632=ORIENTED_EDGE('',*,*,#496,.F.); +#633=ORIENTED_EDGE('',*,*,#498,.F.); +#634=ORIENTED_EDGE('',*,*,#499,.T.); +#635=ORIENTED_EDGE('',*,*,#500,.F.); +#636=ORIENTED_EDGE('',*,*,#499,.F.); +#637=ORIENTED_EDGE('',*,*,#501,.F.); +#638=ORIENTED_EDGE('',*,*,#502,.T.); +#639=ORIENTED_EDGE('',*,*,#503,.F.); +#640=ORIENTED_EDGE('',*,*,#502,.F.); +#641=ORIENTED_EDGE('',*,*,#504,.F.); +#642=ORIENTED_EDGE('',*,*,#505,.T.); +#643=ORIENTED_EDGE('',*,*,#506,.F.); +#644=ORIENTED_EDGE('',*,*,#505,.F.); +#645=ORIENTED_EDGE('',*,*,#507,.F.); +#646=ORIENTED_EDGE('',*,*,#508,.T.); +#647=ORIENTED_EDGE('',*,*,#509,.F.); +#648=ORIENTED_EDGE('',*,*,#508,.F.); +#649=ORIENTED_EDGE('',*,*,#510,.F.); +#650=ORIENTED_EDGE('',*,*,#511,.T.); +#651=ORIENTED_EDGE('',*,*,#512,.F.); +#652=ORIENTED_EDGE('',*,*,#511,.F.); +#653=ORIENTED_EDGE('',*,*,#513,.F.); +#654=ORIENTED_EDGE('',*,*,#514,.T.); +#655=ORIENTED_EDGE('',*,*,#515,.F.); +#656=ORIENTED_EDGE('',*,*,#516,.F.); +#657=ORIENTED_EDGE('',*,*,#517,.F.); +#658=ORIENTED_EDGE('',*,*,#518,.T.); +#659=ORIENTED_EDGE('',*,*,#519,.F.); +#660=ORIENTED_EDGE('',*,*,#520,.F.); +#661=ORIENTED_EDGE('',*,*,#521,.F.); +#662=ORIENTED_EDGE('',*,*,#518,.F.); +#663=ORIENTED_EDGE('',*,*,#522,.F.); +#664=ORIENTED_EDGE('',*,*,#523,.T.); +#665=ORIENTED_EDGE('',*,*,#524,.F.); +#666=ORIENTED_EDGE('',*,*,#525,.T.); +#667=ORIENTED_EDGE('',*,*,#526,.F.); +#668=ORIENTED_EDGE('',*,*,#514,.F.); +#669=ORIENTED_EDGE('',*,*,#527,.F.); +#670=ORIENTED_EDGE('',*,*,#523,.F.); +#671=ORIENTED_EDGE('',*,*,#528,.F.); +#672=ORIENTED_EDGE('',*,*,#529,.T.); +#673=ORIENTED_EDGE('',*,*,#530,.F.); +#674=ORIENTED_EDGE('',*,*,#531,.T.); +#675=ORIENTED_EDGE('',*,*,#532,.F.); +#676=ORIENTED_EDGE('',*,*,#525,.F.); +#677=ORIENTED_EDGE('',*,*,#533,.F.); +#678=ORIENTED_EDGE('',*,*,#529,.F.); +#679=ORIENTED_EDGE('',*,*,#534,.F.); +#680=ORIENTED_EDGE('',*,*,#535,.F.); +#681=ORIENTED_EDGE('',*,*,#536,.F.); +#682=ORIENTED_EDGE('',*,*,#537,.F.); +#683=ORIENTED_EDGE('',*,*,#538,.F.); +#684=ORIENTED_EDGE('',*,*,#531,.F.); +#685=ORIENTED_EDGE('',*,*,#536,.T.); +#686=ORIENTED_EDGE('',*,*,#530,.T.); +#687=ORIENTED_EDGE('',*,*,#524,.T.); +#688=ORIENTED_EDGE('',*,*,#539,.T.); +#689=ORIENTED_EDGE('',*,*,#459,.T.); +#690=ORIENTED_EDGE('',*,*,#465,.T.); +#691=ORIENTED_EDGE('',*,*,#471,.T.); +#692=ORIENTED_EDGE('',*,*,#477,.T.); +#693=ORIENTED_EDGE('',*,*,#483,.T.); +#694=ORIENTED_EDGE('',*,*,#489,.T.); +#695=ORIENTED_EDGE('',*,*,#495,.T.); +#696=ORIENTED_EDGE('',*,*,#513,.T.); +#697=ORIENTED_EDGE('',*,*,#540,.F.); +#698=ORIENTED_EDGE('',*,*,#541,.T.); +#699=ORIENTED_EDGE('',*,*,#539,.F.); +#700=ORIENTED_EDGE('',*,*,#520,.T.); +#701=ORIENTED_EDGE('',*,*,#542,.T.); +#702=ORIENTED_EDGE('',*,*,#543,.T.); +#703=ORIENTED_EDGE('',*,*,#544,.T.); +#704=ORIENTED_EDGE('',*,*,#545,.T.); +#705=ORIENTED_EDGE('',*,*,#546,.T.); +#706=ORIENTED_EDGE('',*,*,#547,.T.); +#707=ORIENTED_EDGE('',*,*,#548,.T.); +#708=ORIENTED_EDGE('',*,*,#549,.T.); +#709=ORIENTED_EDGE('',*,*,#550,.T.); +#710=ORIENTED_EDGE('',*,*,#551,.T.); +#711=ORIENTED_EDGE('',*,*,#540,.T.); +#712=ORIENTED_EDGE('',*,*,#500,.T.); +#713=ORIENTED_EDGE('',*,*,#503,.T.); +#714=ORIENTED_EDGE('',*,*,#506,.T.); +#715=ORIENTED_EDGE('',*,*,#509,.T.); +#716=ORIENTED_EDGE('',*,*,#512,.T.); +#717=ORIENTED_EDGE('',*,*,#519,.T.); +#718=ORIENTED_EDGE('',*,*,#552,.F.); +#719=ORIENTED_EDGE('',*,*,#553,.T.); +#720=ORIENTED_EDGE('',*,*,#542,.F.); +#721=ORIENTED_EDGE('',*,*,#521,.T.); +#722=ORIENTED_EDGE('',*,*,#527,.T.); +#723=ORIENTED_EDGE('',*,*,#533,.T.); +#724=ORIENTED_EDGE('',*,*,#552,.T.); +#725=ORIENTED_EDGE('',*,*,#458,.T.); +#726=ORIENTED_EDGE('',*,*,#464,.T.); +#727=ORIENTED_EDGE('',*,*,#470,.T.); +#728=ORIENTED_EDGE('',*,*,#476,.T.); +#729=ORIENTED_EDGE('',*,*,#482,.T.); +#730=ORIENTED_EDGE('',*,*,#488,.T.); +#731=ORIENTED_EDGE('',*,*,#494,.T.); +#732=ORIENTED_EDGE('',*,*,#535,.T.); +#733=ORIENTED_EDGE('',*,*,#554,.F.); +#734=ORIENTED_EDGE('',*,*,#555,.F.); +#735=ORIENTED_EDGE('',*,*,#556,.T.); +#736=ORIENTED_EDGE('',*,*,#543,.F.); +#737=ORIENTED_EDGE('',*,*,#553,.F.); +#738=ORIENTED_EDGE('',*,*,#537,.T.); +#739=ORIENTED_EDGE('',*,*,#541,.F.); +#740=ORIENTED_EDGE('',*,*,#551,.F.); +#741=ORIENTED_EDGE('',*,*,#557,.F.); +#742=ORIENTED_EDGE('',*,*,#558,.F.); +#743=ORIENTED_EDGE('',*,*,#559,.F.); +#744=ORIENTED_EDGE('',*,*,#544,.F.); +#745=ORIENTED_EDGE('',*,*,#556,.F.); +#746=ORIENTED_EDGE('',*,*,#560,.F.); +#747=ORIENTED_EDGE('',*,*,#561,.T.); +#748=ORIENTED_EDGE('',*,*,#545,.F.); +#749=ORIENTED_EDGE('',*,*,#561,.F.); +#750=ORIENTED_EDGE('',*,*,#562,.F.); +#751=ORIENTED_EDGE('',*,*,#563,.T.); +#752=ORIENTED_EDGE('',*,*,#546,.F.); +#753=ORIENTED_EDGE('',*,*,#563,.F.); +#754=ORIENTED_EDGE('',*,*,#564,.F.); +#755=ORIENTED_EDGE('',*,*,#565,.T.); +#756=ORIENTED_EDGE('',*,*,#547,.F.); +#757=ORIENTED_EDGE('',*,*,#565,.F.); +#758=ORIENTED_EDGE('',*,*,#566,.F.); +#759=ORIENTED_EDGE('',*,*,#567,.T.); +#760=ORIENTED_EDGE('',*,*,#548,.F.); +#761=ORIENTED_EDGE('',*,*,#567,.F.); +#762=ORIENTED_EDGE('',*,*,#568,.F.); +#763=ORIENTED_EDGE('',*,*,#569,.T.); +#764=ORIENTED_EDGE('',*,*,#549,.F.); +#765=ORIENTED_EDGE('',*,*,#569,.F.); +#766=ORIENTED_EDGE('',*,*,#570,.F.); +#767=ORIENTED_EDGE('',*,*,#571,.T.); +#768=ORIENTED_EDGE('',*,*,#550,.F.); +#769=ORIENTED_EDGE('',*,*,#571,.F.); +#770=ORIENTED_EDGE('',*,*,#572,.F.); +#771=ORIENTED_EDGE('',*,*,#557,.T.); +#772=ORIENTED_EDGE('',*,*,#538,.T.); +#773=ORIENTED_EDGE('',*,*,#573,.F.); +#774=ORIENTED_EDGE('',*,*,#526,.T.); +#775=ORIENTED_EDGE('',*,*,#532,.T.); +#776=ORIENTED_EDGE('',*,*,#461,.T.); +#777=ORIENTED_EDGE('',*,*,#467,.T.); +#778=ORIENTED_EDGE('',*,*,#473,.T.); +#779=ORIENTED_EDGE('',*,*,#479,.T.); +#780=ORIENTED_EDGE('',*,*,#485,.T.); +#781=ORIENTED_EDGE('',*,*,#491,.T.); +#782=ORIENTED_EDGE('',*,*,#497,.T.); +#783=ORIENTED_EDGE('',*,*,#515,.T.); +#784=ORIENTED_EDGE('',*,*,#573,.T.); +#785=ORIENTED_EDGE('',*,*,#559,.T.); +#786=ORIENTED_EDGE('',*,*,#574,.T.); +#787=ORIENTED_EDGE('',*,*,#516,.T.); +#788=ORIENTED_EDGE('',*,*,#574,.F.); +#789=ORIENTED_EDGE('',*,*,#558,.T.); +#790=ORIENTED_EDGE('',*,*,#572,.T.); +#791=ORIENTED_EDGE('',*,*,#570,.T.); +#792=ORIENTED_EDGE('',*,*,#568,.T.); +#793=ORIENTED_EDGE('',*,*,#566,.T.); +#794=ORIENTED_EDGE('',*,*,#564,.T.); +#795=ORIENTED_EDGE('',*,*,#562,.T.); +#796=ORIENTED_EDGE('',*,*,#560,.T.); +#797=ORIENTED_EDGE('',*,*,#555,.T.); +#798=ORIENTED_EDGE('',*,*,#575,.F.); +#799=ORIENTED_EDGE('',*,*,#498,.T.); +#800=ORIENTED_EDGE('',*,*,#501,.T.); +#801=ORIENTED_EDGE('',*,*,#504,.T.); +#802=ORIENTED_EDGE('',*,*,#507,.T.); +#803=ORIENTED_EDGE('',*,*,#510,.T.); +#804=ORIENTED_EDGE('',*,*,#517,.T.); +#805=ORIENTED_EDGE('',*,*,#575,.T.); +#806=ORIENTED_EDGE('',*,*,#554,.T.); +#807=ORIENTED_EDGE('',*,*,#576,.T.); +#808=ORIENTED_EDGE('',*,*,#522,.T.); +#809=ORIENTED_EDGE('',*,*,#576,.F.); +#810=ORIENTED_EDGE('',*,*,#534,.T.); +#811=ORIENTED_EDGE('',*,*,#528,.T.); +#812=ORIENTED_EDGE('',*,*,#456,.T.); +#813=ORIENTED_EDGE('',*,*,#462,.T.); +#814=ORIENTED_EDGE('',*,*,#468,.T.); +#815=ORIENTED_EDGE('',*,*,#474,.T.); +#816=ORIENTED_EDGE('',*,*,#480,.T.); +#817=ORIENTED_EDGE('',*,*,#486,.T.); +#818=ORIENTED_EDGE('',*,*,#492,.T.); +#819=CYLINDRICAL_SURFACE('',#908,7.); +#820=CYLINDRICAL_SURFACE('',#911,7.); +#821=CYLINDRICAL_SURFACE('',#914,1.6); +#822=CYLINDRICAL_SURFACE('',#917,1.6); +#823=CYLINDRICAL_SURFACE('',#920,1.6); +#824=CYLINDRICAL_SURFACE('',#923,1.6); +#825=CYLINDRICAL_SURFACE('',#926,1.6); +#826=CYLINDRICAL_SURFACE('',#929,1.6); +#827=CYLINDRICAL_SURFACE('',#932,1.6); +#828=CYLINDRICAL_SURFACE('',#935,1.6); +#829=CYLINDRICAL_SURFACE('',#938,1.6); +#830=CYLINDRICAL_SURFACE('',#941,1.6); +#831=CYLINDRICAL_SURFACE('',#944,1.6); +#832=CYLINDRICAL_SURFACE('',#947,1.6); +#833=CYLINDRICAL_SURFACE('',#950,1.6); +#834=CYLINDRICAL_SURFACE('',#953,1.6); +#835=CYLINDRICAL_SURFACE('',#956,1.6); +#836=CYLINDRICAL_SURFACE('',#959,1.6); +#837=CYLINDRICAL_SURFACE('',#962,1.6); +#838=CYLINDRICAL_SURFACE('',#972,17.5); +#839=CYLINDRICAL_SURFACE('',#975,17.5); +#840=CYLINDRICAL_SURFACE('',#981,0.5); +#841=CYLINDRICAL_SURFACE('',#989,0.5); +#842=CYLINDRICAL_SURFACE('',#997,28.5); +#843=CYLINDRICAL_SURFACE('',#999,3.49999999999998); +#844=CYLINDRICAL_SURFACE('',#1001,21.5); +#845=CYLINDRICAL_SURFACE('',#1003,3.49999999999998); +#846=CYLINDRICAL_SURFACE('',#1005,28.5); +#847=CYLINDRICAL_SURFACE('',#1009,3.); +#848=CYLINDRICAL_SURFACE('',#1011,3.); +#849=ADVANCED_FACE('',(#68),#819,.F.); +#850=ADVANCED_FACE('',(#69),#820,.F.); +#851=ADVANCED_FACE('',(#70),#821,.F.); +#852=ADVANCED_FACE('',(#71),#822,.F.); +#853=ADVANCED_FACE('',(#72),#823,.F.); +#854=ADVANCED_FACE('',(#73),#824,.F.); +#855=ADVANCED_FACE('',(#74),#825,.F.); +#856=ADVANCED_FACE('',(#75),#826,.F.); +#857=ADVANCED_FACE('',(#76),#827,.F.); +#858=ADVANCED_FACE('',(#77),#828,.F.); +#859=ADVANCED_FACE('',(#78),#829,.F.); +#860=ADVANCED_FACE('',(#79),#830,.F.); +#861=ADVANCED_FACE('',(#80),#831,.F.); +#862=ADVANCED_FACE('',(#81),#832,.F.); +#863=ADVANCED_FACE('',(#82),#833,.F.); +#864=ADVANCED_FACE('',(#83),#834,.F.); +#865=ADVANCED_FACE('',(#84),#835,.F.); +#866=ADVANCED_FACE('',(#85),#836,.F.); +#867=ADVANCED_FACE('',(#86),#837,.F.); +#868=ADVANCED_FACE('',(#87),#53,.F.); +#869=ADVANCED_FACE('',(#88),#54,.F.); +#870=ADVANCED_FACE('',(#89),#55,.F.); +#871=ADVANCED_FACE('',(#90),#838,.T.); +#872=ADVANCED_FACE('',(#91),#839,.T.); +#873=ADVANCED_FACE('',(#92),#56,.F.); +#874=ADVANCED_FACE('',(#93),#57,.F.); +#875=ADVANCED_FACE('',(#94,#15,#16,#17,#18,#19,#20,#21),#58,.F.); +#876=ADVANCED_FACE('',(#95),#840,.F.); +#877=ADVANCED_FACE('',(#96,#22,#23,#24,#25,#26),#59,.F.); +#878=ADVANCED_FACE('',(#97),#841,.F.); +#879=ADVANCED_FACE('',(#98,#27,#28,#29,#30,#31,#32,#33),#60,.F.); +#880=ADVANCED_FACE('',(#99),#61,.F.); +#881=ADVANCED_FACE('',(#100),#62,.F.); +#882=ADVANCED_FACE('',(#101),#63,.F.); +#883=ADVANCED_FACE('',(#102),#842,.T.); +#884=ADVANCED_FACE('',(#103),#843,.T.); +#885=ADVANCED_FACE('',(#104),#844,.F.); +#886=ADVANCED_FACE('',(#105),#845,.T.); +#887=ADVANCED_FACE('',(#106),#846,.T.); +#888=ADVANCED_FACE('',(#107),#64,.F.); +#889=ADVANCED_FACE('',(#108,#34,#35,#36,#37,#38,#39,#40),#65,.T.); +#890=ADVANCED_FACE('',(#109),#847,.T.); +#891=ADVANCED_FACE('',(#110,#41,#42,#43,#44,#45),#66,.T.); +#892=ADVANCED_FACE('',(#111),#848,.T.); +#893=ADVANCED_FACE('',(#112,#46,#47,#48,#49,#50,#51,#52),#67,.T.); +#894=CLOSED_SHELL('',(#849,#850,#851,#852,#853,#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)); +#895=DERIVED_UNIT_ELEMENT(#897,1.); +#896=DERIVED_UNIT_ELEMENT(#1536,-3.); +#897=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT(.KILO.,.GRAM.) +); +#898=DERIVED_UNIT((#895,#896)); +#899=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(2680.),#898); +#900=PROPERTY_DEFINITION_REPRESENTATION(#905,#902); +#901=PROPERTY_DEFINITION_REPRESENTATION(#906,#903); +#902=REPRESENTATION('material name',(#904),#1533); +#903=REPRESENTATION('density',(#899),#1533); +#904=DESCRIPTIVE_REPRESENTATION_ITEM('Aluminum 5052','Aluminum 5052'); +#905=PROPERTY_DEFINITION('material property','material name',#1543); +#906=PROPERTY_DEFINITION('material property','density of part',#1543); +#907=AXIS2_PLACEMENT_3D('',#1286,#1013,#1014); +#908=AXIS2_PLACEMENT_3D('',#1287,#1015,#1016); +#909=AXIS2_PLACEMENT_3D('',#1289,#1017,#1018); +#910=AXIS2_PLACEMENT_3D('',#1292,#1020,#1021); +#911=AXIS2_PLACEMENT_3D('',#1293,#1022,#1023); +#912=AXIS2_PLACEMENT_3D('',#1295,#1024,#1025); +#913=AXIS2_PLACEMENT_3D('',#1298,#1027,#1028); +#914=AXIS2_PLACEMENT_3D('',#1299,#1029,#1030); +#915=AXIS2_PLACEMENT_3D('',#1301,#1031,#1032); +#916=AXIS2_PLACEMENT_3D('',#1304,#1034,#1035); +#917=AXIS2_PLACEMENT_3D('',#1305,#1036,#1037); +#918=AXIS2_PLACEMENT_3D('',#1307,#1038,#1039); +#919=AXIS2_PLACEMENT_3D('',#1310,#1041,#1042); +#920=AXIS2_PLACEMENT_3D('',#1311,#1043,#1044); +#921=AXIS2_PLACEMENT_3D('',#1313,#1045,#1046); +#922=AXIS2_PLACEMENT_3D('',#1316,#1048,#1049); +#923=AXIS2_PLACEMENT_3D('',#1317,#1050,#1051); +#924=AXIS2_PLACEMENT_3D('',#1319,#1052,#1053); +#925=AXIS2_PLACEMENT_3D('',#1322,#1055,#1056); +#926=AXIS2_PLACEMENT_3D('',#1323,#1057,#1058); +#927=AXIS2_PLACEMENT_3D('',#1325,#1059,#1060); +#928=AXIS2_PLACEMENT_3D('',#1328,#1062,#1063); +#929=AXIS2_PLACEMENT_3D('',#1329,#1064,#1065); +#930=AXIS2_PLACEMENT_3D('',#1331,#1066,#1067); +#931=AXIS2_PLACEMENT_3D('',#1334,#1069,#1070); +#932=AXIS2_PLACEMENT_3D('',#1335,#1071,#1072); +#933=AXIS2_PLACEMENT_3D('',#1337,#1073,#1074); +#934=AXIS2_PLACEMENT_3D('',#1340,#1076,#1077); +#935=AXIS2_PLACEMENT_3D('',#1341,#1078,#1079); +#936=AXIS2_PLACEMENT_3D('',#1343,#1080,#1081); +#937=AXIS2_PLACEMENT_3D('',#1346,#1083,#1084); +#938=AXIS2_PLACEMENT_3D('',#1347,#1085,#1086); +#939=AXIS2_PLACEMENT_3D('',#1349,#1087,#1088); +#940=AXIS2_PLACEMENT_3D('',#1352,#1090,#1091); +#941=AXIS2_PLACEMENT_3D('',#1353,#1092,#1093); +#942=AXIS2_PLACEMENT_3D('',#1355,#1094,#1095); +#943=AXIS2_PLACEMENT_3D('',#1358,#1097,#1098); +#944=AXIS2_PLACEMENT_3D('',#1359,#1099,#1100); +#945=AXIS2_PLACEMENT_3D('',#1361,#1101,#1102); +#946=AXIS2_PLACEMENT_3D('',#1364,#1104,#1105); +#947=AXIS2_PLACEMENT_3D('',#1365,#1106,#1107); +#948=AXIS2_PLACEMENT_3D('',#1367,#1108,#1109); +#949=AXIS2_PLACEMENT_3D('',#1370,#1111,#1112); +#950=AXIS2_PLACEMENT_3D('',#1371,#1113,#1114); +#951=AXIS2_PLACEMENT_3D('',#1373,#1115,#1116); +#952=AXIS2_PLACEMENT_3D('',#1376,#1118,#1119); +#953=AXIS2_PLACEMENT_3D('',#1377,#1120,#1121); +#954=AXIS2_PLACEMENT_3D('',#1379,#1122,#1123); +#955=AXIS2_PLACEMENT_3D('',#1382,#1125,#1126); +#956=AXIS2_PLACEMENT_3D('',#1383,#1127,#1128); +#957=AXIS2_PLACEMENT_3D('',#1385,#1129,#1130); +#958=AXIS2_PLACEMENT_3D('',#1388,#1132,#1133); +#959=AXIS2_PLACEMENT_3D('',#1389,#1134,#1135); +#960=AXIS2_PLACEMENT_3D('',#1391,#1136,#1137); +#961=AXIS2_PLACEMENT_3D('',#1394,#1139,#1140); +#962=AXIS2_PLACEMENT_3D('',#1395,#1141,#1142); +#963=AXIS2_PLACEMENT_3D('',#1397,#1143,#1144); +#964=AXIS2_PLACEMENT_3D('',#1400,#1146,#1147); +#965=AXIS2_PLACEMENT_3D('',#1401,#1148,#1149); +#966=AXIS2_PLACEMENT_3D('',#1404,#1150,#1151); +#967=AXIS2_PLACEMENT_3D('',#1408,#1153,#1154); +#968=AXIS2_PLACEMENT_3D('',#1412,#1156,#1157); +#969=AXIS2_PLACEMENT_3D('',#1416,#1159,#1160); +#970=AXIS2_PLACEMENT_3D('',#1418,#1162,#1163); +#971=AXIS2_PLACEMENT_3D('',#1424,#1167,#1168); +#972=AXIS2_PLACEMENT_3D('',#1430,#1172,#1173); +#973=AXIS2_PLACEMENT_3D('',#1432,#1174,#1175); +#974=AXIS2_PLACEMENT_3D('',#1434,#1176,#1177); +#975=AXIS2_PLACEMENT_3D('',#1436,#1179,#1180); +#976=AXIS2_PLACEMENT_3D('',#1438,#1181,#1182); +#977=AXIS2_PLACEMENT_3D('',#1441,#1184,#1185); +#978=AXIS2_PLACEMENT_3D('',#1442,#1186,#1187); +#979=AXIS2_PLACEMENT_3D('',#1448,#1191,#1192); +#980=AXIS2_PLACEMENT_3D('',#1454,#1196,#1197); +#981=AXIS2_PLACEMENT_3D('',#1456,#1199,#1200); +#982=AXIS2_PLACEMENT_3D('',#1459,#1202,#1203); +#983=AXIS2_PLACEMENT_3D('',#1460,#1204,#1205); +#984=AXIS2_PLACEMENT_3D('',#1468,#1209,#1210); +#985=AXIS2_PLACEMENT_3D('',#1470,#1211,#1212); +#986=AXIS2_PLACEMENT_3D('',#1472,#1213,#1214); +#987=AXIS2_PLACEMENT_3D('',#1474,#1215,#1216); +#988=AXIS2_PLACEMENT_3D('',#1476,#1217,#1218); +#989=AXIS2_PLACEMENT_3D('',#1480,#1221,#1222); +#990=AXIS2_PLACEMENT_3D('',#1482,#1224,#1225); +#991=AXIS2_PLACEMENT_3D('',#1483,#1226,#1227); +#992=AXIS2_PLACEMENT_3D('',#1484,#1228,#1229); +#993=AXIS2_PLACEMENT_3D('',#1486,#1230,#1231); +#994=AXIS2_PLACEMENT_3D('',#1490,#1234,#1235); +#995=AXIS2_PLACEMENT_3D('',#1495,#1238,#1239); +#996=AXIS2_PLACEMENT_3D('',#1496,#1240,#1241); +#997=AXIS2_PLACEMENT_3D('',#1500,#1244,#1245); +#998=AXIS2_PLACEMENT_3D('',#1502,#1246,#1247); +#999=AXIS2_PLACEMENT_3D('',#1504,#1249,#1250); +#1000=AXIS2_PLACEMENT_3D('',#1506,#1251,#1252); +#1001=AXIS2_PLACEMENT_3D('',#1508,#1254,#1255); +#1002=AXIS2_PLACEMENT_3D('',#1510,#1256,#1257); +#1003=AXIS2_PLACEMENT_3D('',#1512,#1259,#1260); +#1004=AXIS2_PLACEMENT_3D('',#1514,#1261,#1262); +#1005=AXIS2_PLACEMENT_3D('',#1516,#1264,#1265); +#1006=AXIS2_PLACEMENT_3D('',#1518,#1266,#1267); +#1007=AXIS2_PLACEMENT_3D('',#1520,#1269,#1270); +#1008=AXIS2_PLACEMENT_3D('',#1522,#1272,#1273); +#1009=AXIS2_PLACEMENT_3D('',#1524,#1275,#1276); +#1010=AXIS2_PLACEMENT_3D('',#1526,#1278,#1279); +#1011=AXIS2_PLACEMENT_3D('',#1528,#1281,#1282); +#1012=AXIS2_PLACEMENT_3D('',#1530,#1284,#1285); +#1013=DIRECTION('axis',(0.,0.,1.)); +#1014=DIRECTION('refdir',(1.,0.,0.)); +#1015=DIRECTION('center_axis',(-1.,1.01506105108586E-16,0.)); +#1016=DIRECTION('ref_axis',(0.,0.,-1.)); +#1017=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1018=DIRECTION('ref_axis',(0.,0.,-1.)); +#1019=DIRECTION('',(-1.,1.01506105108586E-16,0.)); +#1020=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1021=DIRECTION('ref_axis',(0.,0.,-1.)); +#1022=DIRECTION('center_axis',(-1.,1.01506105108586E-16,0.)); +#1023=DIRECTION('ref_axis',(0.,0.,-1.)); +#1024=DIRECTION('center_axis',(-1.,0.,0.)); +#1025=DIRECTION('ref_axis',(0.,0.,-1.)); +#1026=DIRECTION('',(-1.,1.01506105108586E-16,0.)); +#1027=DIRECTION('center_axis',(1.,0.,0.)); +#1028=DIRECTION('ref_axis',(0.,0.,-1.)); +#1029=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1030=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1031=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1032=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1033=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1034=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1035=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1036=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1037=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1038=DIRECTION('center_axis',(-1.,0.,0.)); +#1039=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1040=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1041=DIRECTION('center_axis',(1.,0.,0.)); +#1042=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1043=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1044=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1045=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1046=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1047=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1048=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1049=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1050=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1051=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1052=DIRECTION('center_axis',(-1.,0.,0.)); +#1053=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1054=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1055=DIRECTION('center_axis',(1.,0.,0.)); +#1056=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1057=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1058=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1059=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1060=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1061=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1062=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1063=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1064=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1065=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1066=DIRECTION('center_axis',(-1.,0.,0.)); +#1067=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1068=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1069=DIRECTION('center_axis',(1.,0.,0.)); +#1070=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1071=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1072=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1073=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1074=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1075=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1076=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1077=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1078=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1079=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1080=DIRECTION('center_axis',(-1.,0.,0.)); +#1081=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1082=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1083=DIRECTION('center_axis',(1.,0.,0.)); +#1084=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1085=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1086=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1087=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1088=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1089=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1090=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1091=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1092=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1093=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1094=DIRECTION('center_axis',(-1.,0.,0.)); +#1095=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1096=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1097=DIRECTION('center_axis',(1.,0.,0.)); +#1098=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1099=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1100=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1101=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1102=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1103=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1104=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1105=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1106=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1107=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1108=DIRECTION('center_axis',(-1.,0.,0.)); +#1109=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1110=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1111=DIRECTION('center_axis',(1.,0.,0.)); +#1112=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1113=DIRECTION('center_axis',(0.,-1.,0.)); +#1114=DIRECTION('ref_axis',(0.,0.,1.)); +#1115=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1116=DIRECTION('ref_axis',(0.,0.,1.)); +#1117=DIRECTION('',(0.,-1.,0.)); +#1118=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1119=DIRECTION('ref_axis',(0.,0.,1.)); +#1120=DIRECTION('center_axis',(0.,-1.,0.)); +#1121=DIRECTION('ref_axis',(0.,0.,1.)); +#1122=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1123=DIRECTION('ref_axis',(0.,0.,1.)); +#1124=DIRECTION('',(0.,-1.,0.)); +#1125=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1126=DIRECTION('ref_axis',(0.,0.,1.)); +#1127=DIRECTION('center_axis',(0.,-1.,0.)); +#1128=DIRECTION('ref_axis',(0.,0.,1.)); +#1129=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1130=DIRECTION('ref_axis',(0.,0.,1.)); +#1131=DIRECTION('',(0.,-1.,0.)); +#1132=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1133=DIRECTION('ref_axis',(0.,0.,1.)); +#1134=DIRECTION('center_axis',(0.,-1.,0.)); +#1135=DIRECTION('ref_axis',(0.,0.,1.)); +#1136=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1137=DIRECTION('ref_axis',(0.,0.,1.)); +#1138=DIRECTION('',(0.,-1.,0.)); +#1139=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1140=DIRECTION('ref_axis',(0.,0.,1.)); +#1141=DIRECTION('center_axis',(0.,-1.,0.)); +#1142=DIRECTION('ref_axis',(0.,0.,1.)); +#1143=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1144=DIRECTION('ref_axis',(0.,0.,1.)); +#1145=DIRECTION('',(0.,-1.,0.)); +#1146=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1147=DIRECTION('ref_axis',(0.,0.,1.)); +#1148=DIRECTION('center_axis',(0.,0.,1.)); +#1149=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1150=DIRECTION('center_axis',(0.,0.,-1.)); +#1151=DIRECTION('ref_axis',(-0.707106781186546,0.707106781186549,0.)); +#1152=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1153=DIRECTION('center_axis',(0.,0.,1.)); +#1154=DIRECTION('ref_axis',(-0.707106781186546,0.707106781186549,0.)); +#1155=DIRECTION('',(-1.,-2.62626810598259E-34,0.)); +#1156=DIRECTION('center_axis',(0.,0.,1.)); +#1157=DIRECTION('ref_axis',(0.707106781186548,0.707106781186548,0.)); +#1158=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1159=DIRECTION('center_axis',(0.,0.,-1.)); +#1160=DIRECTION('ref_axis',(0.707106781186548,0.707106781186547,0.)); +#1161=DIRECTION('',(1.,2.62626810598259E-34,0.)); +#1162=DIRECTION('center_axis',(-8.98439977863692E-17,-0.809242789904336, +0.587474345812519)); +#1163=DIRECTION('ref_axis',(6.5222754509766E-17,0.587474345812519,0.809242789904336)); +#1164=DIRECTION('',(-6.5222754509766E-17,-0.587474345812519,-0.809242789904336)); +#1165=DIRECTION('',(6.5222754509766E-17,0.587474345812519,0.809242789904336)); +#1166=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1167=DIRECTION('center_axis',(-8.98439977863692E-17,-0.809242789904336, +0.587474345812519)); +#1168=DIRECTION('ref_axis',(6.5222754509766E-17,0.587474345812519,0.809242789904336)); +#1169=DIRECTION('',(0.,0.587474345812519,0.809242789904336)); +#1170=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1171=DIRECTION('',(0.,-0.587474345812519,-0.809242789904336)); +#1172=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1173=DIRECTION('ref_axis',(0.,0.,-1.)); +#1174=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1175=DIRECTION('ref_axis',(0.,0.,-1.)); +#1176=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1177=DIRECTION('ref_axis',(0.,0.,-1.)); +#1178=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1179=DIRECTION('center_axis',(-1.,1.11022302462516E-16,0.)); +#1180=DIRECTION('ref_axis',(0.,0.,-1.)); +#1181=DIRECTION('center_axis',(1.,0.,0.)); +#1182=DIRECTION('ref_axis',(0.,0.,-1.)); +#1183=DIRECTION('',(-1.,1.11022302462516E-16,0.)); +#1184=DIRECTION('center_axis',(-1.,0.,0.)); +#1185=DIRECTION('ref_axis',(0.,0.,-1.)); +#1186=DIRECTION('center_axis',(7.05545432005794E-17,0.63549882893485,-0.772101831640383)); +#1187=DIRECTION('ref_axis',(-8.57205230842409E-17,-0.772101831640383,-0.63549882893485)); +#1188=DIRECTION('',(8.57205230842409E-17,0.772101831640383,0.63549882893485)); +#1189=DIRECTION('',(-8.57205230842409E-17,-0.772101831640383,-0.63549882893485)); +#1190=DIRECTION('',(1.,1.92948375329413E-16,2.5019110414088E-16)); +#1191=DIRECTION('center_axis',(7.05545432005794E-17,0.63549882893485,-0.772101831640383)); +#1192=DIRECTION('ref_axis',(-8.57205230842409E-17,-0.772101831640383,-0.63549882893485)); +#1193=DIRECTION('',(0.,-0.772101831640383,-0.63549882893485)); +#1194=DIRECTION('',(1.,1.92948375329413E-16,2.5019110414088E-16)); +#1195=DIRECTION('',(0.,0.772101831640383,0.63549882893485)); +#1196=DIRECTION('center_axis',(-1.,0.,0.)); +#1197=DIRECTION('ref_axis',(0.,-1.,0.)); +#1198=DIRECTION('',(0.,0.,1.)); +#1199=DIRECTION('center_axis',(0.,0.,1.)); +#1200=DIRECTION('ref_axis',(-0.707106781186546,0.707106781186549,0.)); +#1201=DIRECTION('',(0.,0.,-1.)); +#1202=DIRECTION('center_axis',(-2.5019110414088E-16,0.,1.)); +#1203=DIRECTION('ref_axis',(-0.707106781186546,0.707106781186549,0.)); +#1204=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1205=DIRECTION('ref_axis',(-1.,-2.62626810598259E-34,0.)); +#1206=DIRECTION('',(0.,0.,1.)); +#1207=DIRECTION('',(-1.,-2.62626810598259E-34,-2.5019110414088E-16)); +#1208=DIRECTION('',(0.,0.,1.)); +#1209=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1210=DIRECTION('ref_axis',(-1.,0.,0.)); +#1211=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1212=DIRECTION('ref_axis',(-1.,0.,0.)); +#1213=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1214=DIRECTION('ref_axis',(-1.,0.,0.)); +#1215=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1216=DIRECTION('ref_axis',(-1.,0.,0.)); +#1217=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1218=DIRECTION('ref_axis',(-1.,0.,0.)); +#1219=DIRECTION('',(-7.40148848410896E-16,-1.94382931426128E-49,-1.)); +#1220=DIRECTION('',(-1.,-2.62626810598259E-34,-2.5019110414088E-16)); +#1221=DIRECTION('center_axis',(0.,0.,1.)); +#1222=DIRECTION('ref_axis',(0.707106781186548,0.707106781186547,0.)); +#1223=DIRECTION('',(0.,0.,-1.)); +#1224=DIRECTION('center_axis',(-2.5019110414088E-16,0.,1.)); +#1225=DIRECTION('ref_axis',(0.707106781186548,0.707106781186547,0.)); +#1226=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1227=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1228=DIRECTION('center_axis',(2.5019110414088E-16,0.,-1.)); +#1229=DIRECTION('ref_axis',(1.,0.,2.5019110414088E-16)); +#1230=DIRECTION('center_axis',(2.5019110414088E-16,0.,-1.)); +#1231=DIRECTION('ref_axis',(0.707106781186548,0.707106781186548,0.)); +#1232=DIRECTION('',(1.,2.62626810598259E-34,2.5019110414088E-16)); +#1233=DIRECTION('',(0.,-1.,0.)); +#1234=DIRECTION('center_axis',(2.5019110414088E-16,0.,-1.)); +#1235=DIRECTION('ref_axis',(1.,0.,2.5019110414088E-16)); +#1236=DIRECTION('',(0.,-1.,0.)); +#1237=DIRECTION('',(1.,2.62626810598259E-34,2.5019110414088E-16)); +#1238=DIRECTION('center_axis',(2.5019110414088E-16,0.,-1.)); +#1239=DIRECTION('ref_axis',(-0.707106781186546,0.707106781186549,0.)); +#1240=DIRECTION('center_axis',(-1.,0.,0.)); +#1241=DIRECTION('ref_axis',(0.,0.,-1.)); +#1242=DIRECTION('',(0.,0.,-1.)); +#1243=DIRECTION('',(0.,-1.,0.)); +#1244=DIRECTION('center_axis',(0.,-1.,0.)); +#1245=DIRECTION('ref_axis',(0.9659258323746,0.,0.258819022391007)); +#1246=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1247=DIRECTION('ref_axis',(-1.,0.,0.)); +#1248=DIRECTION('',(0.,-1.,0.)); +#1249=DIRECTION('center_axis',(0.,-1.,0.)); +#1250=DIRECTION('ref_axis',(-1.,0.,0.)); +#1251=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1252=DIRECTION('ref_axis',(-1.,0.,0.)); +#1253=DIRECTION('',(0.,-1.,0.)); +#1254=DIRECTION('center_axis',(0.,-1.,0.)); +#1255=DIRECTION('ref_axis',(3.82856869892695E-16,0.,-1.)); +#1256=DIRECTION('center_axis',(2.62626810598259E-34,-1.,0.)); +#1257=DIRECTION('ref_axis',(-1.,0.,0.)); +#1258=DIRECTION('',(0.,-1.,0.)); +#1259=DIRECTION('center_axis',(0.,-1.,0.)); +#1260=DIRECTION('ref_axis',(0.5,0.,0.866025403784439)); +#1261=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1262=DIRECTION('ref_axis',(-1.,0.,0.)); +#1263=DIRECTION('',(0.,-1.,0.)); +#1264=DIRECTION('center_axis',(0.,-1.,0.)); +#1265=DIRECTION('ref_axis',(-1.,0.,0.)); +#1266=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1267=DIRECTION('ref_axis',(-1.,0.,0.)); +#1268=DIRECTION('',(0.,-1.,0.)); +#1269=DIRECTION('center_axis',(1.,0.,-7.40148848410896E-16)); +#1270=DIRECTION('ref_axis',(7.40148848410896E-16,0.,1.)); +#1271=DIRECTION('',(7.40148848410896E-16,1.94382931426128E-49,1.)); +#1272=DIRECTION('center_axis',(-1.,0.,0.)); +#1273=DIRECTION('ref_axis',(0.,-1.,0.)); +#1274=DIRECTION('',(0.,0.,1.)); +#1275=DIRECTION('center_axis',(0.,0.,1.)); +#1276=DIRECTION('ref_axis',(-0.707106781186546,0.707106781186549,0.)); +#1277=DIRECTION('',(0.,0.,-1.)); +#1278=DIRECTION('center_axis',(-2.62626810598259E-34,1.,0.)); +#1279=DIRECTION('ref_axis',(-1.,-2.62626810598259E-34,0.)); +#1280=DIRECTION('',(0.,0.,1.)); +#1281=DIRECTION('center_axis',(0.,0.,1.)); +#1282=DIRECTION('ref_axis',(0.707106781186548,0.707106781186548,0.)); +#1283=DIRECTION('',(0.,0.,-1.)); +#1284=DIRECTION('center_axis',(1.,-1.11022302462516E-16,0.)); +#1285=DIRECTION('ref_axis',(1.11022302462516E-16,1.,0.)); +#1286=CARTESIAN_POINT('',(0.,0.,0.)); +#1287=CARTESIAN_POINT('Origin',(35.5,-41.,17.5)); +#1288=CARTESIAN_POINT('',(35.5,-41.,24.5)); +#1289=CARTESIAN_POINT('Origin',(35.5,-41.,17.5)); +#1290=CARTESIAN_POINT('',(33.,-41.,24.5)); +#1291=CARTESIAN_POINT('',(35.5,-41.,24.5)); +#1292=CARTESIAN_POINT('Origin',(33.,-41.,17.5)); +#1293=CARTESIAN_POINT('Origin',(35.5,-41.,17.5)); +#1294=CARTESIAN_POINT('',(-33.,-41.,24.5)); +#1295=CARTESIAN_POINT('Origin',(-33.,-41.,17.5)); +#1296=CARTESIAN_POINT('',(-35.5,-41.,24.5)); +#1297=CARTESIAN_POINT('',(35.5,-41.,24.5)); +#1298=CARTESIAN_POINT('Origin',(-35.5,-41.,17.5)); +#1299=CARTESIAN_POINT('Origin',(-3.,-52.6913429510899,24.25)); +#1300=CARTESIAN_POINT('',(35.5,-54.2913429510899,24.25)); +#1301=CARTESIAN_POINT('Origin',(35.5,-52.6913429510899,24.25)); +#1302=CARTESIAN_POINT('',(33.,-54.2913429510899,24.25)); +#1303=CARTESIAN_POINT('',(-3.,-54.2913429510899,24.25)); +#1304=CARTESIAN_POINT('Origin',(33.,-52.6913429510899,24.25)); +#1305=CARTESIAN_POINT('Origin',(-3.,-52.6913429510899,24.25)); +#1306=CARTESIAN_POINT('',(-33.,-54.2913429510899,24.25)); +#1307=CARTESIAN_POINT('Origin',(-33.,-52.6913429510899,24.25)); +#1308=CARTESIAN_POINT('',(-35.5,-54.2913429510899,24.25)); +#1309=CARTESIAN_POINT('',(-3.,-54.2913429510899,24.25)); +#1310=CARTESIAN_POINT('Origin',(-35.5,-52.6913429510899,24.25)); +#1311=CARTESIAN_POINT('Origin',(-3.,-41.,4.)); +#1312=CARTESIAN_POINT('',(35.5,-42.6,4.)); +#1313=CARTESIAN_POINT('Origin',(35.5,-41.,4.)); +#1314=CARTESIAN_POINT('',(33.,-42.6,4.)); +#1315=CARTESIAN_POINT('',(-3.,-42.6,4.)); +#1316=CARTESIAN_POINT('Origin',(33.,-41.,4.)); +#1317=CARTESIAN_POINT('Origin',(-3.,-41.,4.)); +#1318=CARTESIAN_POINT('',(-33.,-42.6,4.)); +#1319=CARTESIAN_POINT('Origin',(-33.,-41.,4.)); +#1320=CARTESIAN_POINT('',(-35.5,-42.6,4.)); +#1321=CARTESIAN_POINT('',(-3.,-42.6,4.)); +#1322=CARTESIAN_POINT('Origin',(-35.5,-41.,4.)); +#1323=CARTESIAN_POINT('Origin',(-3.,-29.3086570489101,24.25)); +#1324=CARTESIAN_POINT('',(35.5,-30.9086570489101,24.25)); +#1325=CARTESIAN_POINT('Origin',(35.5,-29.3086570489101,24.25)); +#1326=CARTESIAN_POINT('',(33.,-30.9086570489101,24.25)); +#1327=CARTESIAN_POINT('',(-3.,-30.9086570489101,24.25)); +#1328=CARTESIAN_POINT('Origin',(33.,-29.3086570489101,24.25)); +#1329=CARTESIAN_POINT('Origin',(-3.,-29.3086570489101,24.25)); +#1330=CARTESIAN_POINT('',(-33.,-30.9086570489101,24.25)); +#1331=CARTESIAN_POINT('Origin',(-33.,-29.3086570489101,24.25)); +#1332=CARTESIAN_POINT('',(-35.5,-30.9086570489101,24.25)); +#1333=CARTESIAN_POINT('',(-3.,-30.9086570489101,24.25)); +#1334=CARTESIAN_POINT('Origin',(-35.5,-29.3086570489101,24.25)); +#1335=CARTESIAN_POINT('Origin',(-3.,-29.3086570489101,10.75)); +#1336=CARTESIAN_POINT('',(35.5,-30.9086570489101,10.75)); +#1337=CARTESIAN_POINT('Origin',(35.5,-29.3086570489101,10.75)); +#1338=CARTESIAN_POINT('',(33.,-30.9086570489101,10.75)); +#1339=CARTESIAN_POINT('',(-3.,-30.9086570489101,10.75)); +#1340=CARTESIAN_POINT('Origin',(33.,-29.3086570489101,10.75)); +#1341=CARTESIAN_POINT('Origin',(-3.,-29.3086570489101,10.75)); +#1342=CARTESIAN_POINT('',(-33.,-30.9086570489101,10.75)); +#1343=CARTESIAN_POINT('Origin',(-33.,-29.3086570489101,10.75)); +#1344=CARTESIAN_POINT('',(-35.5,-30.9086570489101,10.75)); +#1345=CARTESIAN_POINT('',(-3.,-30.9086570489101,10.75)); +#1346=CARTESIAN_POINT('Origin',(-35.5,-29.3086570489101,10.75)); +#1347=CARTESIAN_POINT('Origin',(-3.,-52.6913429510899,10.75)); +#1348=CARTESIAN_POINT('',(35.5,-54.2913429510899,10.75)); +#1349=CARTESIAN_POINT('Origin',(35.5,-52.6913429510899,10.75)); +#1350=CARTESIAN_POINT('',(33.,-54.2913429510899,10.75)); +#1351=CARTESIAN_POINT('',(-3.,-54.2913429510899,10.75)); +#1352=CARTESIAN_POINT('Origin',(33.,-52.6913429510899,10.75)); +#1353=CARTESIAN_POINT('Origin',(-3.,-52.6913429510899,10.75)); +#1354=CARTESIAN_POINT('',(-33.,-54.2913429510899,10.75)); +#1355=CARTESIAN_POINT('Origin',(-33.,-52.6913429510899,10.75)); +#1356=CARTESIAN_POINT('',(-35.5,-54.2913429510899,10.75)); +#1357=CARTESIAN_POINT('',(-3.,-54.2913429510899,10.75)); +#1358=CARTESIAN_POINT('Origin',(-35.5,-52.6913429510899,10.75)); +#1359=CARTESIAN_POINT('Origin',(-3.,-41.,31.)); +#1360=CARTESIAN_POINT('',(35.5,-42.6,31.)); +#1361=CARTESIAN_POINT('Origin',(35.5,-41.,31.)); +#1362=CARTESIAN_POINT('',(33.,-42.6,31.)); +#1363=CARTESIAN_POINT('',(-3.,-42.6,31.)); +#1364=CARTESIAN_POINT('Origin',(33.,-41.,31.)); +#1365=CARTESIAN_POINT('Origin',(-3.,-41.,31.)); +#1366=CARTESIAN_POINT('',(-33.,-42.6,31.)); +#1367=CARTESIAN_POINT('Origin',(-33.,-41.,31.)); +#1368=CARTESIAN_POINT('',(-35.5,-42.6,31.)); +#1369=CARTESIAN_POINT('',(-3.,-42.6,31.)); +#1370=CARTESIAN_POINT('Origin',(-35.5,-41.,31.)); +#1371=CARTESIAN_POINT('Origin',(21.650635094611,-36.,92.)); +#1372=CARTESIAN_POINT('',(21.650635094611,2.5,90.4)); +#1373=CARTESIAN_POINT('Origin',(21.650635094611,2.5,92.)); +#1374=CARTESIAN_POINT('',(21.650635094611,-5.14600132751099E-50,90.4)); +#1375=CARTESIAN_POINT('',(21.650635094611,-36.,90.4)); +#1376=CARTESIAN_POINT('Origin',(21.650635094611,0.,92.)); +#1377=CARTESIAN_POINT('Origin',(-2.46519032881566E-31,-36.,54.5)); +#1378=CARTESIAN_POINT('',(1.95943487863576E-16,2.5,52.9)); +#1379=CARTESIAN_POINT('Origin',(-2.46519032881566E-31,2.5,54.5)); +#1380=CARTESIAN_POINT('',(-1.95943487863577E-16,-5.14600132751099E-50,52.9)); +#1381=CARTESIAN_POINT('',(1.95943487863576E-16,-36.,52.9)); +#1382=CARTESIAN_POINT('Origin',(-2.46519032881566E-31,0.,54.5)); +#1383=CARTESIAN_POINT('Origin',(-21.650635094611,-36.,67.)); +#1384=CARTESIAN_POINT('',(-21.650635094611,2.5,65.4)); +#1385=CARTESIAN_POINT('Origin',(-21.650635094611,2.5,67.)); +#1386=CARTESIAN_POINT('',(-21.650635094611,-5.14600132751099E-50,65.4)); +#1387=CARTESIAN_POINT('',(-21.650635094611,-36.,65.4)); +#1388=CARTESIAN_POINT('Origin',(-21.650635094611,0.,67.)); +#1389=CARTESIAN_POINT('Origin',(21.650635094611,-36.,67.)); +#1390=CARTESIAN_POINT('',(21.650635094611,2.5,65.4)); +#1391=CARTESIAN_POINT('Origin',(21.650635094611,2.5,67.)); +#1392=CARTESIAN_POINT('',(21.650635094611,-5.14600132751099E-50,65.4)); +#1393=CARTESIAN_POINT('',(21.650635094611,-36.,65.4)); +#1394=CARTESIAN_POINT('Origin',(21.650635094611,0.,67.)); +#1395=CARTESIAN_POINT('Origin',(-21.650635094611,-36.,92.)); +#1396=CARTESIAN_POINT('',(-21.650635094611,2.5,90.4)); +#1397=CARTESIAN_POINT('Origin',(-21.650635094611,2.5,92.)); +#1398=CARTESIAN_POINT('',(-21.650635094611,-5.14600132751099E-50,90.4)); +#1399=CARTESIAN_POINT('',(-21.650635094611,-36.,90.4)); +#1400=CARTESIAN_POINT('Origin',(-21.650635094611,0.,92.)); +#1401=CARTESIAN_POINT('Origin',(35.5,-0.499999999999998,43.5)); +#1402=CARTESIAN_POINT('',(-33.,-0.499999999999991,43.5)); +#1403=CARTESIAN_POINT('',(-32.5,0.,43.5)); +#1404=CARTESIAN_POINT('Origin',(-32.5,-0.5,43.5)); +#1405=CARTESIAN_POINT('',(-35.5,-0.499999999999991,43.5)); +#1406=CARTESIAN_POINT('',(35.5,-0.499999999999999,43.5)); +#1407=CARTESIAN_POINT('',(-32.5,2.50000000000001,43.5)); +#1408=CARTESIAN_POINT('Origin',(-32.5,-0.5,43.5)); +#1409=CARTESIAN_POINT('',(32.5,2.5,43.5)); +#1410=CARTESIAN_POINT('',(34.25,2.5,43.5)); +#1411=CARTESIAN_POINT('',(35.5,-0.499999999999999,43.5)); +#1412=CARTESIAN_POINT('Origin',(32.5,-0.499999999999998,43.5)); +#1413=CARTESIAN_POINT('',(33.,-0.499999999999998,43.5)); +#1414=CARTESIAN_POINT('',(35.5,-0.499999999999999,43.5)); +#1415=CARTESIAN_POINT('',(32.5,0.,43.5)); +#1416=CARTESIAN_POINT('Origin',(32.5,-0.499999999999998,43.5)); +#1417=CARTESIAN_POINT('',(34.25,0.,43.5)); +#1418=CARTESIAN_POINT('Origin',(35.5,-26.8382511766742,7.21919894828059)); +#1419=CARTESIAN_POINT('',(33.,-26.8382511766742,7.21919894828059)); +#1420=CARTESIAN_POINT('',(33.,-37.7280423257094,-7.78143049832529)); +#1421=CARTESIAN_POINT('',(35.5,-26.8382511766742,7.21919894828059)); +#1422=CARTESIAN_POINT('',(35.5,-37.7280423257094,-7.78143049832529)); +#1423=CARTESIAN_POINT('',(35.5,-26.8382511766742,7.21919894828059)); +#1424=CARTESIAN_POINT('Origin',(35.5,-26.8382511766742,7.21919894828059)); +#1425=CARTESIAN_POINT('',(-33.,-26.8382511766742,7.21919894828059)); +#1426=CARTESIAN_POINT('',(-33.,-23.9229980461955,11.2349446457766)); +#1427=CARTESIAN_POINT('',(-35.5,-26.8382511766742,7.21919894828059)); +#1428=CARTESIAN_POINT('',(35.5,-26.8382511766742,7.21919894828059)); +#1429=CARTESIAN_POINT('',(-35.5,-23.9229980461955,11.2349446457766)); +#1430=CARTESIAN_POINT('Origin',(35.5,-41.,17.5)); +#1431=CARTESIAN_POINT('',(33.,-52.1212295063599,31.0117820537067)); +#1432=CARTESIAN_POINT('Origin',(33.,-41.,17.5)); +#1433=CARTESIAN_POINT('',(35.5,-52.1212295063599,31.0117820537067)); +#1434=CARTESIAN_POINT('Origin',(35.5,-41.,17.5)); +#1435=CARTESIAN_POINT('',(35.5,-52.1212295063599,31.0117820537067)); +#1436=CARTESIAN_POINT('Origin',(35.5,-41.,17.5)); +#1437=CARTESIAN_POINT('',(-33.,-52.1212295063599,31.0117820537067)); +#1438=CARTESIAN_POINT('Origin',(-33.,-41.,17.5)); +#1439=CARTESIAN_POINT('',(-35.5,-52.1212295063599,31.0117820537067)); +#1440=CARTESIAN_POINT('',(35.5,-52.1212295063599,31.0117820537067)); +#1441=CARTESIAN_POINT('Origin',(-35.5,-41.,17.5)); +#1442=CARTESIAN_POINT('Origin',(35.5,-0.499999999999999,73.5)); +#1443=CARTESIAN_POINT('',(33.,-0.499999999999998,73.5)); +#1444=CARTESIAN_POINT('',(33.,-42.2287297383942,39.1540655714443)); +#1445=CARTESIAN_POINT('',(35.5,-0.499999999999998,73.5)); +#1446=CARTESIAN_POINT('',(35.5,-42.2287297383942,39.1540655714443)); +#1447=CARTESIAN_POINT('',(32.,-0.499999999999997,73.5)); +#1448=CARTESIAN_POINT('Origin',(35.5,-0.499999999999999,73.5)); +#1449=CARTESIAN_POINT('',(-33.,-0.5,73.5)); +#1450=CARTESIAN_POINT('',(-33.,-18.3830802014968,58.7808579644809)); +#1451=CARTESIAN_POINT('',(-35.5,-0.5,73.5)); +#1452=CARTESIAN_POINT('',(2.89422562994119E-16,-0.500000000000001,73.5)); +#1453=CARTESIAN_POINT('',(-35.5,-18.3830802014968,58.7808579644809)); +#1454=CARTESIAN_POINT('Origin',(-33.,8.66668474974256E-33,0.)); +#1455=CARTESIAN_POINT('',(-33.,-0.5,0.)); +#1456=CARTESIAN_POINT('Origin',(-32.5,-0.5,0.)); +#1457=CARTESIAN_POINT('',(-32.5,0.,73.5)); +#1458=CARTESIAN_POINT('',(-32.5,0.,0.)); +#1459=CARTESIAN_POINT('Origin',(-32.5,-0.5,73.5)); +#1460=CARTESIAN_POINT('Origin',(33.,8.66668474974256E-33,0.)); +#1461=CARTESIAN_POINT('',(32.5,0.,73.5)); +#1462=CARTESIAN_POINT('',(32.5,0.,0.)); +#1463=CARTESIAN_POINT('',(28.5,0.,73.5)); +#1464=CARTESIAN_POINT('',(30.75,0.,73.5)); +#1465=CARTESIAN_POINT('',(28.5,0.,79.4999986597767)); +#1466=CARTESIAN_POINT('',(28.5,0.,39.7499993298883)); +#1467=CARTESIAN_POINT('',(24.6817240078565,0.,93.75)); +#1468=CARTESIAN_POINT('Origin',(0.,0.,79.5)); +#1469=CARTESIAN_POINT('',(18.6195461813655,0.,90.25)); +#1470=CARTESIAN_POINT('Origin',(21.650635094611,0.,92.)); +#1471=CARTESIAN_POINT('',(-18.6195461813655,0.,90.25)); +#1472=CARTESIAN_POINT('Origin',(0.,0.,79.5)); +#1473=CARTESIAN_POINT('',(-24.6817240078565,0.,93.75)); +#1474=CARTESIAN_POINT('Origin',(-21.650635094611,0.,92.)); +#1475=CARTESIAN_POINT('',(-28.5,0.,79.4999986597767)); +#1476=CARTESIAN_POINT('Origin',(0.,0.,79.5)); +#1477=CARTESIAN_POINT('',(-28.5,0.,73.5)); +#1478=CARTESIAN_POINT('',(-28.5,0.,36.75)); +#1479=CARTESIAN_POINT('',(-1.25000000000001,0.,73.5)); +#1480=CARTESIAN_POINT('Origin',(32.5,-0.499999999999998,0.)); +#1481=CARTESIAN_POINT('',(33.,-0.499999999999998,0.)); +#1482=CARTESIAN_POINT('Origin',(32.5,-0.499999999999998,73.5)); +#1483=CARTESIAN_POINT('Origin',(33.,-80.,0.)); +#1484=CARTESIAN_POINT('Origin',(28.5,2.5,73.5)); +#1485=CARTESIAN_POINT('',(32.5,2.5,73.5)); +#1486=CARTESIAN_POINT('Origin',(32.5,-0.499999999999998,73.5)); +#1487=CARTESIAN_POINT('',(28.5,2.5,73.5)); +#1488=CARTESIAN_POINT('',(30.75,2.5,73.5)); +#1489=CARTESIAN_POINT('',(28.5,2.5,73.5)); +#1490=CARTESIAN_POINT('Origin',(-35.5,2.5,73.5)); +#1491=CARTESIAN_POINT('',(-28.5,2.5,73.5)); +#1492=CARTESIAN_POINT('',(-28.5,2.5,73.5)); +#1493=CARTESIAN_POINT('',(-32.5,2.5,73.5)); +#1494=CARTESIAN_POINT('',(-1.25000000000001,2.5,73.5)); +#1495=CARTESIAN_POINT('Origin',(-32.5,-0.5,73.5)); +#1496=CARTESIAN_POINT('Origin',(28.5,2.5,79.4999986597767)); +#1497=CARTESIAN_POINT('',(28.5,2.5,79.4999986597767)); +#1498=CARTESIAN_POINT('',(28.5,2.5,39.7499993298883)); +#1499=CARTESIAN_POINT('',(28.5,2.5,79.4999986597767)); +#1500=CARTESIAN_POINT('Origin',(0.,2.5,79.5)); +#1501=CARTESIAN_POINT('',(24.6817240078565,2.5,93.75)); +#1502=CARTESIAN_POINT('Origin',(0.,2.5,79.5)); +#1503=CARTESIAN_POINT('',(24.6817240078565,2.5,93.75)); +#1504=CARTESIAN_POINT('Origin',(21.650635094611,2.5,92.)); +#1505=CARTESIAN_POINT('',(18.6195461813655,2.5,90.25)); +#1506=CARTESIAN_POINT('Origin',(21.650635094611,2.5,92.)); +#1507=CARTESIAN_POINT('',(18.6195461813655,2.5,90.25)); +#1508=CARTESIAN_POINT('Origin',(0.,2.5,79.5)); +#1509=CARTESIAN_POINT('',(-18.6195461813655,2.5,90.25)); +#1510=CARTESIAN_POINT('Origin',(0.,2.5,79.5)); +#1511=CARTESIAN_POINT('',(-18.6195461813655,2.5,90.25)); +#1512=CARTESIAN_POINT('Origin',(-21.650635094611,2.5,92.)); +#1513=CARTESIAN_POINT('',(-24.6817240078565,2.5,93.75)); +#1514=CARTESIAN_POINT('Origin',(-21.650635094611,2.5,92.)); +#1515=CARTESIAN_POINT('',(-24.6817240078565,2.5,93.75)); +#1516=CARTESIAN_POINT('Origin',(0.,2.5,79.5)); +#1517=CARTESIAN_POINT('',(-28.5,2.5,79.4999986597767)); +#1518=CARTESIAN_POINT('Origin',(0.,2.5,79.5)); +#1519=CARTESIAN_POINT('',(-28.5,2.5,79.4999986597767)); +#1520=CARTESIAN_POINT('Origin',(-28.5,2.5,73.5)); +#1521=CARTESIAN_POINT('',(-28.5,2.5,36.75)); +#1522=CARTESIAN_POINT('Origin',(-35.5,8.66668474974256E-33,0.)); +#1523=CARTESIAN_POINT('',(-35.5,-0.5,0.)); +#1524=CARTESIAN_POINT('Origin',(-32.5,-0.5,0.)); +#1525=CARTESIAN_POINT('',(-32.5,2.5,0.)); +#1526=CARTESIAN_POINT('Origin',(33.,2.5,0.)); +#1527=CARTESIAN_POINT('',(32.5,2.5,0.)); +#1528=CARTESIAN_POINT('Origin',(32.5,-0.499999999999998,0.)); +#1529=CARTESIAN_POINT('',(35.5,-0.499999999999999,0.)); +#1530=CARTESIAN_POINT('Origin',(35.5,-80.,0.)); +#1531=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1535, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1532=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#1535, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#1533=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1531)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1535,#1537,#1538)) +REPRESENTATION_CONTEXT('','3D') +); +#1534=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#1532)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#1535,#1537,#1538)) +REPRESENTATION_CONTEXT('','3D') +); +#1535=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#1536=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT($,.METRE.) +); +#1537=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#1538=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#1539=SHAPE_DEFINITION_REPRESENTATION(#1540,#1541); +#1540=PRODUCT_DEFINITION_SHAPE('',$,#1543); +#1541=SHAPE_REPRESENTATION('',(#907),#1533); +#1542=PRODUCT_DEFINITION_CONTEXT('part definition',#1547,'design'); +#1543=PRODUCT_DEFINITION('link4-5','link4-5 v2',#1544,#1542); +#1544=PRODUCT_DEFINITION_FORMATION('',$,#1549); +#1545=PRODUCT_RELATED_PRODUCT_CATEGORY('link4-5 v2','link4-5 v2',(#1549)); +#1546=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#1547); +#1547=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#1548=PRODUCT_CONTEXT('part definition',#1547,'mechanical'); +#1549=PRODUCT('link4-5','link4-5 v2',$,(#1548)); +#1550=PRESENTATION_STYLE_ASSIGNMENT((#1551)); +#1551=SURFACE_STYLE_USAGE(.BOTH.,#1552); +#1552=SURFACE_SIDE_STYLE('',(#1553)); +#1553=SURFACE_STYLE_FILL_AREA(#1554); +#1554=FILL_AREA_STYLE('Aluminum - Satin',(#1555)); +#1555=FILL_AREA_STYLE_COLOUR('Aluminum - Satin',#1556); +#1556=COLOUR_RGB('Aluminum - Satin',0.96078431372549,0.96078431372549,0.964705882352941); +ENDSEC; +END-ISO-10303-21; diff --git a/hardware/follower_STEPs/link5-6_v0.2.0.step b/hardware/follower_STEPs/link5-6_v0.2.0.step new file mode 100644 index 0000000000000000000000000000000000000000..4a180d818cde9d30b6775d4fa8968265be0e5471 --- /dev/null +++ b/hardware/follower_STEPs/link5-6_v0.2.0.step @@ -0,0 +1,720 @@ +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 */ 'link5-6_v0.2.0.step', +/* time_stamp */ '2025-10-08T20:57:35+02:00', +/* author */ (''), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v20.1', +/* originating_system */ 'Autodesk Translation Framework v14.17.0.0', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#635); +#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#642,#12); +#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#634); +#13=STYLED_ITEM('',(#652),#14); +#14=MANIFOLD_SOLID_BREP('Body1',#367); +#15=FACE_BOUND('',#61,.T.); +#16=FACE_BOUND('',#62,.T.); +#17=FACE_BOUND('',#63,.T.); +#18=FACE_BOUND('',#64,.T.); +#19=FACE_BOUND('',#74,.T.); +#20=FACE_BOUND('',#75,.T.); +#21=FACE_BOUND('',#76,.T.); +#22=FACE_BOUND('',#77,.T.); +#23=FACE_BOUND('',#79,.T.); +#24=FACE_BOUND('',#80,.T.); +#25=FACE_BOUND('',#81,.T.); +#26=FACE_BOUND('',#82,.T.); +#27=FACE_BOUND('',#85,.T.); +#28=FACE_BOUND('',#86,.T.); +#29=FACE_BOUND('',#87,.T.); +#30=FACE_BOUND('',#88,.T.); +#31=PLANE('',#396); +#32=PLANE('',#409); +#33=PLANE('',#415); +#34=PLANE('',#419); +#35=PLANE('',#420); +#36=PLANE('',#422); +#37=FACE_OUTER_BOUND('',#55,.T.); +#38=FACE_OUTER_BOUND('',#56,.T.); +#39=FACE_OUTER_BOUND('',#57,.T.); +#40=FACE_OUTER_BOUND('',#58,.T.); +#41=FACE_OUTER_BOUND('',#59,.T.); +#42=FACE_OUTER_BOUND('',#60,.T.); +#43=FACE_OUTER_BOUND('',#65,.T.); +#44=FACE_OUTER_BOUND('',#66,.T.); +#45=FACE_OUTER_BOUND('',#67,.T.); +#46=FACE_OUTER_BOUND('',#68,.T.); +#47=FACE_OUTER_BOUND('',#69,.T.); +#48=FACE_OUTER_BOUND('',#70,.T.); +#49=FACE_OUTER_BOUND('',#71,.T.); +#50=FACE_OUTER_BOUND('',#72,.T.); +#51=FACE_OUTER_BOUND('',#73,.T.); +#52=FACE_OUTER_BOUND('',#78,.T.); +#53=FACE_OUTER_BOUND('',#83,.T.); +#54=FACE_OUTER_BOUND('',#84,.T.); +#55=EDGE_LOOP('',(#241,#242,#243,#244)); +#56=EDGE_LOOP('',(#245,#246,#247,#248)); +#57=EDGE_LOOP('',(#249,#250,#251,#252)); +#58=EDGE_LOOP('',(#253,#254,#255,#256)); +#59=EDGE_LOOP('',(#257,#258,#259,#260)); +#60=EDGE_LOOP('',(#261,#262,#263,#264)); +#61=EDGE_LOOP('',(#265)); +#62=EDGE_LOOP('',(#266)); +#63=EDGE_LOOP('',(#267)); +#64=EDGE_LOOP('',(#268)); +#65=EDGE_LOOP('',(#269,#270,#271,#272)); +#66=EDGE_LOOP('',(#273,#274,#275,#276)); +#67=EDGE_LOOP('',(#277,#278,#279,#280)); +#68=EDGE_LOOP('',(#281,#282,#283,#284)); +#69=EDGE_LOOP('',(#285,#286,#287,#288,#289,#290,#291,#292)); +#70=EDGE_LOOP('',(#293,#294,#295,#296)); +#71=EDGE_LOOP('',(#297,#298,#299,#300,#301,#302,#303,#304)); +#72=EDGE_LOOP('',(#305,#306,#307,#308)); +#73=EDGE_LOOP('',(#309,#310,#311,#312)); +#74=EDGE_LOOP('',(#313)); +#75=EDGE_LOOP('',(#314)); +#76=EDGE_LOOP('',(#315)); +#77=EDGE_LOOP('',(#316)); +#78=EDGE_LOOP('',(#317,#318,#319,#320)); +#79=EDGE_LOOP('',(#321)); +#80=EDGE_LOOP('',(#322)); +#81=EDGE_LOOP('',(#323)); +#82=EDGE_LOOP('',(#324)); +#83=EDGE_LOOP('',(#325,#326,#327,#328)); +#84=EDGE_LOOP('',(#329,#330,#331,#332)); +#85=EDGE_LOOP('',(#333)); +#86=EDGE_LOOP('',(#334)); +#87=EDGE_LOOP('',(#335)); +#88=EDGE_LOOP('',(#336)); +#89=LINE('',#538,#113); +#90=LINE('',#544,#114); +#91=LINE('',#550,#115); +#92=LINE('',#556,#116); +#93=LINE('',#563,#117); +#94=LINE('',#566,#118); +#95=LINE('',#569,#119); +#96=LINE('',#571,#120); +#97=LINE('',#572,#121); +#98=LINE('',#577,#122); +#99=LINE('',#583,#123); +#100=LINE('',#589,#124); +#101=LINE('',#595,#125); +#102=LINE('',#601,#126); +#103=LINE('',#603,#127); +#104=LINE('',#605,#128); +#105=LINE('',#608,#129); +#106=LINE('',#614,#130); +#107=LINE('',#619,#131); +#108=LINE('',#622,#132); +#109=LINE('',#623,#133); +#110=LINE('',#625,#134); +#111=LINE('',#627,#135); +#112=LINE('',#629,#136); +#113=VECTOR('',#429,1.6); +#114=VECTOR('',#436,1.6); +#115=VECTOR('',#443,1.6); +#116=VECTOR('',#450,1.6); +#117=VECTOR('',#457,10.); +#118=VECTOR('',#460,10.); +#119=VECTOR('',#463,10.); +#120=VECTOR('',#464,10.); +#121=VECTOR('',#465,10.); +#122=VECTOR('',#470,1.6); +#123=VECTOR('',#477,1.6); +#124=VECTOR('',#484,1.6); +#125=VECTOR('',#491,1.6); +#126=VECTOR('',#498,10.); +#127=VECTOR('',#499,10.); +#128=VECTOR('',#500,10.); +#129=VECTOR('',#503,10.); +#130=VECTOR('',#510,10.); +#131=VECTOR('',#515,10.); +#132=VECTOR('',#518,10.); +#133=VECTOR('',#519,10.); +#134=VECTOR('',#522,10.); +#135=VECTOR('',#525,10.); +#136=VECTOR('',#528,10.); +#137=CIRCLE('',#382,1.6); +#138=CIRCLE('',#383,1.6); +#139=CIRCLE('',#385,1.6); +#140=CIRCLE('',#386,1.6); +#141=CIRCLE('',#388,1.6); +#142=CIRCLE('',#389,1.6); +#143=CIRCLE('',#391,1.6); +#144=CIRCLE('',#392,1.6); +#145=CIRCLE('',#394,23.5); +#146=CIRCLE('',#395,23.5); +#147=CIRCLE('',#398,1.6); +#148=CIRCLE('',#399,1.6); +#149=CIRCLE('',#401,1.6); +#150=CIRCLE('',#402,1.6); +#151=CIRCLE('',#404,1.6); +#152=CIRCLE('',#405,1.6); +#153=CIRCLE('',#407,1.6); +#154=CIRCLE('',#408,1.6); +#155=CIRCLE('',#410,4.1); +#156=CIRCLE('',#411,0.1); +#157=CIRCLE('',#413,17.5); +#158=CIRCLE('',#414,17.5); +#159=CIRCLE('',#416,4.1); +#160=CIRCLE('',#417,0.1); +#161=VERTEX_POINT('',#535); +#162=VERTEX_POINT('',#537); +#163=VERTEX_POINT('',#541); +#164=VERTEX_POINT('',#543); +#165=VERTEX_POINT('',#547); +#166=VERTEX_POINT('',#549); +#167=VERTEX_POINT('',#553); +#168=VERTEX_POINT('',#555); +#169=VERTEX_POINT('',#559); +#170=VERTEX_POINT('',#560); +#171=VERTEX_POINT('',#562); +#172=VERTEX_POINT('',#564); +#173=VERTEX_POINT('',#568); +#174=VERTEX_POINT('',#570); +#175=VERTEX_POINT('',#574); +#176=VERTEX_POINT('',#576); +#177=VERTEX_POINT('',#580); +#178=VERTEX_POINT('',#582); +#179=VERTEX_POINT('',#586); +#180=VERTEX_POINT('',#588); +#181=VERTEX_POINT('',#592); +#182=VERTEX_POINT('',#594); +#183=VERTEX_POINT('',#598); +#184=VERTEX_POINT('',#600); +#185=VERTEX_POINT('',#602); +#186=VERTEX_POINT('',#604); +#187=VERTEX_POINT('',#606); +#188=VERTEX_POINT('',#610); +#189=VERTEX_POINT('',#612); +#190=VERTEX_POINT('',#616); +#191=VERTEX_POINT('',#618); +#192=VERTEX_POINT('',#620); +#193=EDGE_CURVE('',#161,#161,#137,.T.); +#194=EDGE_CURVE('',#161,#162,#89,.T.); +#195=EDGE_CURVE('',#162,#162,#138,.T.); +#196=EDGE_CURVE('',#163,#163,#139,.T.); +#197=EDGE_CURVE('',#163,#164,#90,.T.); +#198=EDGE_CURVE('',#164,#164,#140,.T.); +#199=EDGE_CURVE('',#165,#165,#141,.T.); +#200=EDGE_CURVE('',#165,#166,#91,.T.); +#201=EDGE_CURVE('',#166,#166,#142,.T.); +#202=EDGE_CURVE('',#167,#167,#143,.T.); +#203=EDGE_CURVE('',#167,#168,#92,.T.); +#204=EDGE_CURVE('',#168,#168,#144,.T.); +#205=EDGE_CURVE('',#169,#170,#145,.T.); +#206=EDGE_CURVE('',#171,#169,#93,.T.); +#207=EDGE_CURVE('',#172,#171,#146,.T.); +#208=EDGE_CURVE('',#172,#170,#94,.T.); +#209=EDGE_CURVE('',#173,#172,#95,.T.); +#210=EDGE_CURVE('',#171,#174,#96,.T.); +#211=EDGE_CURVE('',#173,#174,#97,.T.); +#212=EDGE_CURVE('',#175,#175,#147,.T.); +#213=EDGE_CURVE('',#175,#176,#98,.T.); +#214=EDGE_CURVE('',#176,#176,#148,.T.); +#215=EDGE_CURVE('',#177,#177,#149,.T.); +#216=EDGE_CURVE('',#177,#178,#99,.T.); +#217=EDGE_CURVE('',#178,#178,#150,.T.); +#218=EDGE_CURVE('',#179,#179,#151,.T.); +#219=EDGE_CURVE('',#179,#180,#100,.T.); +#220=EDGE_CURVE('',#180,#180,#152,.T.); +#221=EDGE_CURVE('',#181,#181,#153,.T.); +#222=EDGE_CURVE('',#181,#182,#101,.T.); +#223=EDGE_CURVE('',#182,#182,#154,.T.); +#224=EDGE_CURVE('',#183,#173,#155,.T.); +#225=EDGE_CURVE('',#184,#183,#102,.T.); +#226=EDGE_CURVE('',#184,#185,#103,.T.); +#227=EDGE_CURVE('',#186,#185,#104,.T.); +#228=EDGE_CURVE('',#187,#186,#156,.T.); +#229=EDGE_CURVE('',#170,#187,#105,.T.); +#230=EDGE_CURVE('',#185,#188,#157,.T.); +#231=EDGE_CURVE('',#189,#184,#158,.T.); +#232=EDGE_CURVE('',#189,#188,#106,.T.); +#233=EDGE_CURVE('',#174,#190,#159,.T.); +#234=EDGE_CURVE('',#191,#169,#107,.T.); +#235=EDGE_CURVE('',#192,#191,#160,.T.); +#236=EDGE_CURVE('',#188,#192,#108,.T.); +#237=EDGE_CURVE('',#190,#189,#109,.T.); +#238=EDGE_CURVE('',#190,#183,#110,.T.); +#239=EDGE_CURVE('',#192,#186,#111,.T.); +#240=EDGE_CURVE('',#187,#191,#112,.T.); +#241=ORIENTED_EDGE('',*,*,#193,.F.); +#242=ORIENTED_EDGE('',*,*,#194,.T.); +#243=ORIENTED_EDGE('',*,*,#195,.F.); +#244=ORIENTED_EDGE('',*,*,#194,.F.); +#245=ORIENTED_EDGE('',*,*,#196,.F.); +#246=ORIENTED_EDGE('',*,*,#197,.T.); +#247=ORIENTED_EDGE('',*,*,#198,.F.); +#248=ORIENTED_EDGE('',*,*,#197,.F.); +#249=ORIENTED_EDGE('',*,*,#199,.F.); +#250=ORIENTED_EDGE('',*,*,#200,.T.); +#251=ORIENTED_EDGE('',*,*,#201,.F.); +#252=ORIENTED_EDGE('',*,*,#200,.F.); +#253=ORIENTED_EDGE('',*,*,#202,.F.); +#254=ORIENTED_EDGE('',*,*,#203,.T.); +#255=ORIENTED_EDGE('',*,*,#204,.F.); +#256=ORIENTED_EDGE('',*,*,#203,.F.); +#257=ORIENTED_EDGE('',*,*,#205,.F.); +#258=ORIENTED_EDGE('',*,*,#206,.F.); +#259=ORIENTED_EDGE('',*,*,#207,.F.); +#260=ORIENTED_EDGE('',*,*,#208,.T.); +#261=ORIENTED_EDGE('',*,*,#209,.T.); +#262=ORIENTED_EDGE('',*,*,#207,.T.); +#263=ORIENTED_EDGE('',*,*,#210,.T.); +#264=ORIENTED_EDGE('',*,*,#211,.F.); +#265=ORIENTED_EDGE('',*,*,#193,.T.); +#266=ORIENTED_EDGE('',*,*,#196,.T.); +#267=ORIENTED_EDGE('',*,*,#199,.T.); +#268=ORIENTED_EDGE('',*,*,#202,.T.); +#269=ORIENTED_EDGE('',*,*,#212,.F.); +#270=ORIENTED_EDGE('',*,*,#213,.T.); +#271=ORIENTED_EDGE('',*,*,#214,.F.); +#272=ORIENTED_EDGE('',*,*,#213,.F.); +#273=ORIENTED_EDGE('',*,*,#215,.F.); +#274=ORIENTED_EDGE('',*,*,#216,.T.); +#275=ORIENTED_EDGE('',*,*,#217,.F.); +#276=ORIENTED_EDGE('',*,*,#216,.F.); +#277=ORIENTED_EDGE('',*,*,#218,.F.); +#278=ORIENTED_EDGE('',*,*,#219,.T.); +#279=ORIENTED_EDGE('',*,*,#220,.F.); +#280=ORIENTED_EDGE('',*,*,#219,.F.); +#281=ORIENTED_EDGE('',*,*,#221,.F.); +#282=ORIENTED_EDGE('',*,*,#222,.T.); +#283=ORIENTED_EDGE('',*,*,#223,.F.); +#284=ORIENTED_EDGE('',*,*,#222,.F.); +#285=ORIENTED_EDGE('',*,*,#224,.F.); +#286=ORIENTED_EDGE('',*,*,#225,.F.); +#287=ORIENTED_EDGE('',*,*,#226,.T.); +#288=ORIENTED_EDGE('',*,*,#227,.F.); +#289=ORIENTED_EDGE('',*,*,#228,.F.); +#290=ORIENTED_EDGE('',*,*,#229,.F.); +#291=ORIENTED_EDGE('',*,*,#208,.F.); +#292=ORIENTED_EDGE('',*,*,#209,.F.); +#293=ORIENTED_EDGE('',*,*,#230,.F.); +#294=ORIENTED_EDGE('',*,*,#226,.F.); +#295=ORIENTED_EDGE('',*,*,#231,.F.); +#296=ORIENTED_EDGE('',*,*,#232,.T.); +#297=ORIENTED_EDGE('',*,*,#233,.F.); +#298=ORIENTED_EDGE('',*,*,#210,.F.); +#299=ORIENTED_EDGE('',*,*,#206,.T.); +#300=ORIENTED_EDGE('',*,*,#234,.F.); +#301=ORIENTED_EDGE('',*,*,#235,.F.); +#302=ORIENTED_EDGE('',*,*,#236,.F.); +#303=ORIENTED_EDGE('',*,*,#232,.F.); +#304=ORIENTED_EDGE('',*,*,#237,.F.); +#305=ORIENTED_EDGE('',*,*,#224,.T.); +#306=ORIENTED_EDGE('',*,*,#211,.T.); +#307=ORIENTED_EDGE('',*,*,#233,.T.); +#308=ORIENTED_EDGE('',*,*,#238,.T.); +#309=ORIENTED_EDGE('',*,*,#227,.T.); +#310=ORIENTED_EDGE('',*,*,#230,.T.); +#311=ORIENTED_EDGE('',*,*,#236,.T.); +#312=ORIENTED_EDGE('',*,*,#239,.T.); +#313=ORIENTED_EDGE('',*,*,#214,.T.); +#314=ORIENTED_EDGE('',*,*,#217,.T.); +#315=ORIENTED_EDGE('',*,*,#220,.T.); +#316=ORIENTED_EDGE('',*,*,#223,.T.); +#317=ORIENTED_EDGE('',*,*,#229,.T.); +#318=ORIENTED_EDGE('',*,*,#240,.T.); +#319=ORIENTED_EDGE('',*,*,#234,.T.); +#320=ORIENTED_EDGE('',*,*,#205,.T.); +#321=ORIENTED_EDGE('',*,*,#195,.T.); +#322=ORIENTED_EDGE('',*,*,#198,.T.); +#323=ORIENTED_EDGE('',*,*,#201,.T.); +#324=ORIENTED_EDGE('',*,*,#204,.T.); +#325=ORIENTED_EDGE('',*,*,#228,.T.); +#326=ORIENTED_EDGE('',*,*,#239,.F.); +#327=ORIENTED_EDGE('',*,*,#235,.T.); +#328=ORIENTED_EDGE('',*,*,#240,.F.); +#329=ORIENTED_EDGE('',*,*,#225,.T.); +#330=ORIENTED_EDGE('',*,*,#238,.F.); +#331=ORIENTED_EDGE('',*,*,#237,.T.); +#332=ORIENTED_EDGE('',*,*,#231,.T.); +#333=ORIENTED_EDGE('',*,*,#212,.T.); +#334=ORIENTED_EDGE('',*,*,#215,.T.); +#335=ORIENTED_EDGE('',*,*,#218,.T.); +#336=ORIENTED_EDGE('',*,*,#221,.T.); +#337=CYLINDRICAL_SURFACE('',#381,1.6); +#338=CYLINDRICAL_SURFACE('',#384,1.6); +#339=CYLINDRICAL_SURFACE('',#387,1.6); +#340=CYLINDRICAL_SURFACE('',#390,1.6); +#341=CYLINDRICAL_SURFACE('',#393,23.5); +#342=CYLINDRICAL_SURFACE('',#397,1.6); +#343=CYLINDRICAL_SURFACE('',#400,1.6); +#344=CYLINDRICAL_SURFACE('',#403,1.6); +#345=CYLINDRICAL_SURFACE('',#406,1.6); +#346=CYLINDRICAL_SURFACE('',#412,17.5); +#347=CYLINDRICAL_SURFACE('',#418,4.1); +#348=CYLINDRICAL_SURFACE('',#421,0.1); +#349=ADVANCED_FACE('',(#37),#337,.F.); +#350=ADVANCED_FACE('',(#38),#338,.F.); +#351=ADVANCED_FACE('',(#39),#339,.F.); +#352=ADVANCED_FACE('',(#40),#340,.F.); +#353=ADVANCED_FACE('',(#41),#341,.T.); +#354=ADVANCED_FACE('',(#42,#15,#16,#17,#18),#31,.T.); +#355=ADVANCED_FACE('',(#43),#342,.F.); +#356=ADVANCED_FACE('',(#44),#343,.F.); +#357=ADVANCED_FACE('',(#45),#344,.F.); +#358=ADVANCED_FACE('',(#46),#345,.F.); +#359=ADVANCED_FACE('',(#47),#32,.F.); +#360=ADVANCED_FACE('',(#48),#346,.T.); +#361=ADVANCED_FACE('',(#49),#33,.F.); +#362=ADVANCED_FACE('',(#50),#347,.T.); +#363=ADVANCED_FACE('',(#51,#19,#20,#21,#22),#34,.F.); +#364=ADVANCED_FACE('',(#52,#23,#24,#25,#26),#35,.F.); +#365=ADVANCED_FACE('',(#53),#348,.F.); +#366=ADVANCED_FACE('',(#54,#27,#28,#29,#30),#36,.T.); +#367=CLOSED_SHELL('',(#349,#350,#351,#352,#353,#354,#355,#356,#357,#358, +#359,#360,#361,#362,#363,#364,#365,#366)); +#368=DERIVED_UNIT_ELEMENT(#370,1.); +#369=DERIVED_UNIT_ELEMENT(#637,-3.); +#370=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT(.KILO.,.GRAM.) +); +#371=DERIVED_UNIT((#368,#369)); +#372=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(7850.),#371); +#373=PROPERTY_DEFINITION_REPRESENTATION(#378,#375); +#374=PROPERTY_DEFINITION_REPRESENTATION(#379,#376); +#375=REPRESENTATION('material name',(#377),#634); +#376=REPRESENTATION('density',(#372),#634); +#377=DESCRIPTIVE_REPRESENTATION_ITEM('Steel','Steel'); +#378=PROPERTY_DEFINITION('material property','material name',#644); +#379=PROPERTY_DEFINITION('material property','density of part',#644); +#380=AXIS2_PLACEMENT_3D('',#533,#423,#424); +#381=AXIS2_PLACEMENT_3D('',#534,#425,#426); +#382=AXIS2_PLACEMENT_3D('',#536,#427,#428); +#383=AXIS2_PLACEMENT_3D('',#539,#430,#431); +#384=AXIS2_PLACEMENT_3D('',#540,#432,#433); +#385=AXIS2_PLACEMENT_3D('',#542,#434,#435); +#386=AXIS2_PLACEMENT_3D('',#545,#437,#438); +#387=AXIS2_PLACEMENT_3D('',#546,#439,#440); +#388=AXIS2_PLACEMENT_3D('',#548,#441,#442); +#389=AXIS2_PLACEMENT_3D('',#551,#444,#445); +#390=AXIS2_PLACEMENT_3D('',#552,#446,#447); +#391=AXIS2_PLACEMENT_3D('',#554,#448,#449); +#392=AXIS2_PLACEMENT_3D('',#557,#451,#452); +#393=AXIS2_PLACEMENT_3D('',#558,#453,#454); +#394=AXIS2_PLACEMENT_3D('',#561,#455,#456); +#395=AXIS2_PLACEMENT_3D('',#565,#458,#459); +#396=AXIS2_PLACEMENT_3D('',#567,#461,#462); +#397=AXIS2_PLACEMENT_3D('',#573,#466,#467); +#398=AXIS2_PLACEMENT_3D('',#575,#468,#469); +#399=AXIS2_PLACEMENT_3D('',#578,#471,#472); +#400=AXIS2_PLACEMENT_3D('',#579,#473,#474); +#401=AXIS2_PLACEMENT_3D('',#581,#475,#476); +#402=AXIS2_PLACEMENT_3D('',#584,#478,#479); +#403=AXIS2_PLACEMENT_3D('',#585,#480,#481); +#404=AXIS2_PLACEMENT_3D('',#587,#482,#483); +#405=AXIS2_PLACEMENT_3D('',#590,#485,#486); +#406=AXIS2_PLACEMENT_3D('',#591,#487,#488); +#407=AXIS2_PLACEMENT_3D('',#593,#489,#490); +#408=AXIS2_PLACEMENT_3D('',#596,#492,#493); +#409=AXIS2_PLACEMENT_3D('',#597,#494,#495); +#410=AXIS2_PLACEMENT_3D('',#599,#496,#497); +#411=AXIS2_PLACEMENT_3D('',#607,#501,#502); +#412=AXIS2_PLACEMENT_3D('',#609,#504,#505); +#413=AXIS2_PLACEMENT_3D('',#611,#506,#507); +#414=AXIS2_PLACEMENT_3D('',#613,#508,#509); +#415=AXIS2_PLACEMENT_3D('',#615,#511,#512); +#416=AXIS2_PLACEMENT_3D('',#617,#513,#514); +#417=AXIS2_PLACEMENT_3D('',#621,#516,#517); +#418=AXIS2_PLACEMENT_3D('',#624,#520,#521); +#419=AXIS2_PLACEMENT_3D('',#626,#523,#524); +#420=AXIS2_PLACEMENT_3D('',#628,#526,#527); +#421=AXIS2_PLACEMENT_3D('',#630,#529,#530); +#422=AXIS2_PLACEMENT_3D('',#631,#531,#532); +#423=DIRECTION('axis',(0.,0.,1.)); +#424=DIRECTION('refdir',(1.,0.,0.)); +#425=DIRECTION('center_axis',(0.,-1.55820775385987E-16,1.)); +#426=DIRECTION('ref_axis',(-1.,0.,0.)); +#427=DIRECTION('center_axis',(0.,-4.67462326157992E-16,1.)); +#428=DIRECTION('ref_axis',(-1.,0.,0.)); +#429=DIRECTION('',(0.,-1.55820775385987E-16,1.)); +#430=DIRECTION('center_axis',(0.,4.67462326157992E-16,-1.)); +#431=DIRECTION('ref_axis',(-1.,0.,0.)); +#432=DIRECTION('center_axis',(0.,-1.55820775385987E-16,1.)); +#433=DIRECTION('ref_axis',(-1.,0.,0.)); +#434=DIRECTION('center_axis',(0.,-4.67462326157992E-16,1.)); +#435=DIRECTION('ref_axis',(-1.,0.,0.)); +#436=DIRECTION('',(0.,-1.55820775385987E-16,1.)); +#437=DIRECTION('center_axis',(0.,4.67462326157992E-16,-1.)); +#438=DIRECTION('ref_axis',(-1.,0.,0.)); +#439=DIRECTION('center_axis',(0.,-1.55820775385987E-16,1.)); +#440=DIRECTION('ref_axis',(-1.,0.,0.)); +#441=DIRECTION('center_axis',(0.,-4.67462326157992E-16,1.)); +#442=DIRECTION('ref_axis',(-1.,0.,0.)); +#443=DIRECTION('',(0.,-1.55820775385987E-16,1.)); +#444=DIRECTION('center_axis',(0.,4.67462326157992E-16,-1.)); +#445=DIRECTION('ref_axis',(-1.,0.,0.)); +#446=DIRECTION('center_axis',(0.,-1.55820775385987E-16,1.)); +#447=DIRECTION('ref_axis',(-1.,0.,0.)); +#448=DIRECTION('center_axis',(0.,-4.67462326157992E-16,1.)); +#449=DIRECTION('ref_axis',(-1.,0.,0.)); +#450=DIRECTION('',(0.,-1.55820775385987E-16,1.)); +#451=DIRECTION('center_axis',(0.,4.67462326157992E-16,-1.)); +#452=DIRECTION('ref_axis',(-1.,0.,0.)); +#453=DIRECTION('center_axis',(0.,0.,1.)); +#454=DIRECTION('ref_axis',(-6.12323399573677E-17,-1.,0.)); +#455=DIRECTION('center_axis',(0.,-4.67462326157992E-16,1.)); +#456=DIRECTION('ref_axis',(-1.,0.,0.)); +#457=DIRECTION('',(0.,0.,1.)); +#458=DIRECTION('center_axis',(0.,4.67462326157992E-16,-1.)); +#459=DIRECTION('ref_axis',(-1.,0.,0.)); +#460=DIRECTION('',(0.,0.,1.)); +#461=DIRECTION('center_axis',(0.,4.67462326157992E-16,-1.)); +#462=DIRECTION('ref_axis',(0.,1.,4.67462326157992E-16)); +#463=DIRECTION('',(2.54859902415143E-32,-1.,-4.67462326157992E-16)); +#464=DIRECTION('',(2.54859902415143E-32,1.,4.67462326157992E-16)); +#465=DIRECTION('',(-1.,0.,0.)); +#466=DIRECTION('center_axis',(0.,-1.,-2.04178930845092E-16)); +#467=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#468=DIRECTION('center_axis',(0.,-1.,-3.28625990152979E-13)); +#469=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#470=DIRECTION('',(0.,-1.,-2.04178930845092E-16)); +#471=DIRECTION('center_axis',(0.,1.,3.28625990152979E-13)); +#472=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#473=DIRECTION('center_axis',(0.,-1.,-2.04178930845092E-16)); +#474=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#475=DIRECTION('center_axis',(0.,-1.,-3.28625990152979E-13)); +#476=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#477=DIRECTION('',(0.,-1.,-2.04178930845092E-16)); +#478=DIRECTION('center_axis',(0.,1.,3.28625990152979E-13)); +#479=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#480=DIRECTION('center_axis',(0.,-1.,-2.04178930845092E-16)); +#481=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#482=DIRECTION('center_axis',(0.,-1.,-3.28625990152979E-13)); +#483=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#484=DIRECTION('',(0.,-1.,-2.04178930845092E-16)); +#485=DIRECTION('center_axis',(0.,1.,3.28625990152979E-13)); +#486=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#487=DIRECTION('center_axis',(0.,-1.,-2.04178930845092E-16)); +#488=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#489=DIRECTION('center_axis',(0.,-1.,-3.28625990152979E-13)); +#490=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#491=DIRECTION('',(0.,-1.,-2.04178930845092E-16)); +#492=DIRECTION('center_axis',(0.,1.,3.28625990152979E-13)); +#493=DIRECTION('ref_axis',(0.,-2.04178930845092E-16,1.)); +#494=DIRECTION('center_axis',(-1.,2.64127535230203E-32,-1.11022302462496E-16)); +#495=DIRECTION('ref_axis',(1.11022302462496E-16,2.04178930845092E-16,-1.)); +#496=DIRECTION('center_axis',(-1.,2.64127535230203E-32,-1.11022302462496E-16)); +#497=DIRECTION('ref_axis',(0.,0.707106781186673,-0.707106781186422)); +#498=DIRECTION('',(1.11022302462496E-16,3.28625990152979E-13,-1.)); +#499=DIRECTION('',(0.,-1.,-2.37904933848248E-16)); +#500=DIRECTION('',(-1.11022302462496E-16,-3.28625990152979E-13,1.)); +#501=DIRECTION('center_axis',(1.,-2.64127535230203E-32,1.11022302462496E-16)); +#502=DIRECTION('ref_axis',(0.,0.707106781186673,-0.707106781186422)); +#503=DIRECTION('',(-2.54859902415143E-32,1.,4.67462326157992E-16)); +#504=DIRECTION('center_axis',(0.,-1.,-2.37904933848248E-16)); +#505=DIRECTION('ref_axis',(-1.,0.,0.)); +#506=DIRECTION('center_axis',(0.,-1.,-3.28625990152979E-13)); +#507=DIRECTION('ref_axis',(-1.,0.,0.)); +#508=DIRECTION('center_axis',(0.,1.,3.28625990152979E-13)); +#509=DIRECTION('ref_axis',(-1.,0.,0.)); +#510=DIRECTION('',(0.,-1.,-2.37904933848248E-16)); +#511=DIRECTION('center_axis',(1.,2.64127535230203E-32,-1.11022302462496E-16)); +#512=DIRECTION('ref_axis',(1.11022302462496E-16,-2.04178930845092E-16,1.)); +#513=DIRECTION('center_axis',(1.,2.64127535230203E-32,-1.11022302462496E-16)); +#514=DIRECTION('ref_axis',(0.,0.707106781186673,-0.707106781186422)); +#515=DIRECTION('',(-2.54859902415143E-32,-1.,-4.67462326157992E-16)); +#516=DIRECTION('center_axis',(-1.,-2.64127535230203E-32,1.11022302462496E-16)); +#517=DIRECTION('ref_axis',(0.,0.707106781186673,-0.707106781186422)); +#518=DIRECTION('',(-1.11022302462496E-16,3.28625990152979E-13,-1.)); +#519=DIRECTION('',(1.11022302462496E-16,-3.28625990152979E-13,1.)); +#520=DIRECTION('center_axis',(1.,0.,0.)); +#521=DIRECTION('ref_axis',(0.,0.707106781186673,-0.707106781186422)); +#522=DIRECTION('',(1.,0.,0.)); +#523=DIRECTION('center_axis',(0.,1.,3.28625990152979E-13)); +#524=DIRECTION('ref_axis',(0.,-3.28625990152979E-13,1.)); +#525=DIRECTION('',(1.,0.,0.)); +#526=DIRECTION('center_axis',(0.,4.67462326157992E-16,-1.)); +#527=DIRECTION('ref_axis',(0.,1.,4.67462326157992E-16)); +#528=DIRECTION('',(-1.,0.,0.)); +#529=DIRECTION('center_axis',(1.,0.,0.)); +#530=DIRECTION('ref_axis',(0.,0.707106781186673,-0.707106781186422)); +#531=DIRECTION('center_axis',(0.,1.,3.28625990152979E-13)); +#532=DIRECTION('ref_axis',(0.,-3.28625990152979E-13,1.)); +#533=CARTESIAN_POINT('',(0.,0.,0.)); +#534=CARTESIAN_POINT('Origin',(-13.4350288425444,-13.4350288425444,12.9999999999969)); +#535=CARTESIAN_POINT('',(-11.8350288425444,-13.4350288425444,-25.5000000000031)); +#536=CARTESIAN_POINT('Origin',(-13.4350288425444,-13.4350288425444,-25.5000000000031)); +#537=CARTESIAN_POINT('',(-11.8350288425444,-13.4350288425444,-21.5000000000031)); +#538=CARTESIAN_POINT('',(-11.8350288425444,-13.4350288425444,12.9999999999969)); +#539=CARTESIAN_POINT('Origin',(-13.4350288425444,-13.4350288425444,-21.5000000000031)); +#540=CARTESIAN_POINT('Origin',(13.4350288425444,13.4350288425444,12.9999999999969)); +#541=CARTESIAN_POINT('',(15.0350288425444,13.4350288425444,-25.5000000000031)); +#542=CARTESIAN_POINT('Origin',(13.4350288425444,13.4350288425444,-25.5000000000031)); +#543=CARTESIAN_POINT('',(15.0350288425444,13.4350288425444,-21.5000000000031)); +#544=CARTESIAN_POINT('',(15.0350288425444,13.4350288425444,12.9999999999969)); +#545=CARTESIAN_POINT('Origin',(13.4350288425444,13.4350288425444,-21.5000000000031)); +#546=CARTESIAN_POINT('Origin',(-13.4350288425444,13.4350288425444,12.9999999999969)); +#547=CARTESIAN_POINT('',(-11.8350288425444,13.4350288425444,-25.5000000000031)); +#548=CARTESIAN_POINT('Origin',(-13.4350288425444,13.4350288425444,-25.5000000000031)); +#549=CARTESIAN_POINT('',(-11.8350288425444,13.4350288425444,-21.5000000000031)); +#550=CARTESIAN_POINT('',(-11.8350288425444,13.4350288425444,12.9999999999969)); +#551=CARTESIAN_POINT('Origin',(-13.4350288425444,13.4350288425444,-21.5000000000031)); +#552=CARTESIAN_POINT('Origin',(13.4350288425444,-13.4350288425444,12.9999999999969)); +#553=CARTESIAN_POINT('',(15.0350288425444,-13.4350288425444,-25.5000000000031)); +#554=CARTESIAN_POINT('Origin',(13.4350288425444,-13.4350288425444,-25.5000000000031)); +#555=CARTESIAN_POINT('',(15.0350288425444,-13.4350288425444,-21.5000000000031)); +#556=CARTESIAN_POINT('',(15.0350288425444,-13.4350288425444,12.9999999999969)); +#557=CARTESIAN_POINT('Origin',(13.4350288425444,-13.4350288425444,-21.5000000000031)); +#558=CARTESIAN_POINT('Origin',(0.,4.59671287388808E-15,-25.5000000000031)); +#559=CARTESIAN_POINT('',(-17.5,15.6843871413581,-21.500000000003)); +#560=CARTESIAN_POINT('',(17.5,15.6843871413581,-21.500000000003)); +#561=CARTESIAN_POINT('Origin',(0.,4.59671287388808E-15,-21.5000000000031)); +#562=CARTESIAN_POINT('',(-17.5,15.6843871413581,-25.500000000003)); +#563=CARTESIAN_POINT('',(-17.5,15.6843871413581,-25.500000000003)); +#564=CARTESIAN_POINT('',(17.5,15.6843871413581,-25.500000000003)); +#565=CARTESIAN_POINT('Origin',(0.,4.59671287388808E-15,-25.5000000000031)); +#566=CARTESIAN_POINT('',(17.5,15.6843871413581,-25.500000000003)); +#567=CARTESIAN_POINT('Origin',(0.,-28.4999999999998,-25.5000000000031)); +#568=CARTESIAN_POINT('',(17.5,33.399999999984,-25.5000000000031)); +#569=CARTESIAN_POINT('',(17.5,4.49999999998854,-25.5000000000031)); +#570=CARTESIAN_POINT('',(-17.5,33.399999999984,-25.5000000000031)); +#571=CARTESIAN_POINT('',(-17.5,4.49999999998854,-25.5000000000031)); +#572=CARTESIAN_POINT('',(0.,33.399999999984,-25.500000000003)); +#573=CARTESIAN_POINT('Origin',(11.6913429510899,-1.00000000002308,-12.2499999999995)); +#574=CARTESIAN_POINT('',(11.6913429510899,37.499999999984,-13.8499999999995)); +#575=CARTESIAN_POINT('Origin',(11.6913429510899,37.499999999984,-12.2499999999995)); +#576=CARTESIAN_POINT('',(11.6913429510899,33.499999999984,-13.8499999999995)); +#577=CARTESIAN_POINT('',(11.6913429510899,-1.00000000002308,-13.8499999999995)); +#578=CARTESIAN_POINT('Origin',(11.6913429510899,33.499999999984,-12.2499999999995)); +#579=CARTESIAN_POINT('Origin',(-11.6913429510899,-1.00000000002308,1.25000000000049)); +#580=CARTESIAN_POINT('',(-11.6913429510899,37.499999999984,-0.349999999999504)); +#581=CARTESIAN_POINT('Origin',(-11.6913429510899,37.499999999984,1.2500000000005)); +#582=CARTESIAN_POINT('',(-11.6913429510899,33.499999999984,-0.349999999999505)); +#583=CARTESIAN_POINT('',(-11.6913429510899,-1.00000000002308,-0.349999999999512)); +#584=CARTESIAN_POINT('Origin',(-11.6913429510899,33.499999999984,1.2500000000005)); +#585=CARTESIAN_POINT('Origin',(-11.6913429510899,-1.00000000002308,-12.2499999999995)); +#586=CARTESIAN_POINT('',(-11.6913429510899,37.499999999984,-13.8499999999995)); +#587=CARTESIAN_POINT('Origin',(-11.6913429510899,37.499999999984,-12.2499999999995)); +#588=CARTESIAN_POINT('',(-11.6913429510899,33.499999999984,-13.8499999999995)); +#589=CARTESIAN_POINT('',(-11.6913429510899,-1.00000000002308,-13.8499999999995)); +#590=CARTESIAN_POINT('Origin',(-11.6913429510899,33.499999999984,-12.2499999999995)); +#591=CARTESIAN_POINT('Origin',(11.6913429510899,-1.00000000002308,1.25000000000049)); +#592=CARTESIAN_POINT('',(11.6913429510899,37.499999999984,-0.349999999999499)); +#593=CARTESIAN_POINT('Origin',(11.6913429510899,37.499999999984,1.2500000000005)); +#594=CARTESIAN_POINT('',(11.6913429510899,33.499999999984,-0.3499999999995)); +#595=CARTESIAN_POINT('',(11.6913429510899,-1.00000000002308,-0.349999999999507)); +#596=CARTESIAN_POINT('Origin',(11.6913429510899,33.499999999984,1.2500000000005)); +#597=CARTESIAN_POINT('Origin',(17.5,37.4999999999769,-5.4999999999995)); +#598=CARTESIAN_POINT('',(17.5,37.4999999999769,-21.400000000003)); +#599=CARTESIAN_POINT('Origin',(17.5,33.399999999984,-21.400000000003)); +#600=CARTESIAN_POINT('',(17.5,37.4999999999769,-5.4999999999995)); +#601=CARTESIAN_POINT('',(17.5,37.4999999999814,-13.5000000000006)); +#602=CARTESIAN_POINT('',(17.5,33.4999999999787,-5.4999999999995)); +#603=CARTESIAN_POINT('',(17.5,37.4999999999769,-5.4999999999995)); +#604=CARTESIAN_POINT('',(17.5,33.4999999999839,-21.400000000003)); +#605=CARTESIAN_POINT('',(17.5,33.4999999999814,-13.5000000000019)); +#606=CARTESIAN_POINT('',(17.5,33.399999999984,-21.500000000003)); +#607=CARTESIAN_POINT('Origin',(17.5,33.399999999984,-21.400000000003)); +#608=CARTESIAN_POINT('',(17.5,4.49999999998854,-21.500000000003)); +#609=CARTESIAN_POINT('Origin',(0.,37.4999999999769,-5.4999999999995)); +#610=CARTESIAN_POINT('',(-17.5,33.4999999999787,-5.4999999999995)); +#611=CARTESIAN_POINT('Origin',(0.,33.499999999984,-5.4999999999995)); +#612=CARTESIAN_POINT('',(-17.5,37.4999999999769,-5.4999999999995)); +#613=CARTESIAN_POINT('Origin',(0.,37.499999999984,-5.4999999999995)); +#614=CARTESIAN_POINT('',(-17.5,37.4999999999769,-5.4999999999995)); +#615=CARTESIAN_POINT('Origin',(-17.5,37.4999999999769,-25.5000000000031)); +#616=CARTESIAN_POINT('',(-17.5,37.4999999999769,-21.400000000003)); +#617=CARTESIAN_POINT('Origin',(-17.5,33.399999999984,-21.400000000003)); +#618=CARTESIAN_POINT('',(-17.5,33.399999999984,-21.500000000003)); +#619=CARTESIAN_POINT('',(-17.5,4.49999999998854,-21.500000000003)); +#620=CARTESIAN_POINT('',(-17.5,33.4999999999839,-21.400000000003)); +#621=CARTESIAN_POINT('Origin',(-17.5,33.399999999984,-21.400000000003)); +#622=CARTESIAN_POINT('',(-17.5,33.4999999999846,-23.5000000000037)); +#623=CARTESIAN_POINT('',(-17.5,37.4999999999846,-23.5000000000024)); +#624=CARTESIAN_POINT('Origin',(0.,33.399999999984,-21.400000000003)); +#625=CARTESIAN_POINT('',(0.,37.4999999999839,-21.4000000000017)); +#626=CARTESIAN_POINT('Origin',(0.,33.499999999984,-21.5000000000031)); +#627=CARTESIAN_POINT('',(0.,33.4999999999839,-21.400000000003)); +#628=CARTESIAN_POINT('Origin',(0.,-28.4999999999998,-21.5000000000031)); +#629=CARTESIAN_POINT('',(0.,33.399999999984,-21.500000000003)); +#630=CARTESIAN_POINT('Origin',(0.,33.399999999984,-21.400000000003)); +#631=CARTESIAN_POINT('Origin',(0.,37.499999999984,-21.5000000000017)); +#632=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#636, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#633=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#636, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#634=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#632)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#636,#638,#639)) +REPRESENTATION_CONTEXT('','3D') +); +#635=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#633)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#636,#638,#639)) +REPRESENTATION_CONTEXT('','3D') +); +#636=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#637=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT($,.METRE.) +); +#638=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#639=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#640=SHAPE_DEFINITION_REPRESENTATION(#641,#642); +#641=PRODUCT_DEFINITION_SHAPE('',$,#644); +#642=SHAPE_REPRESENTATION('',(#380),#634); +#643=PRODUCT_DEFINITION_CONTEXT('part definition',#648,'design'); +#644=PRODUCT_DEFINITION('link5-6','link5-6 v2',#645,#643); +#645=PRODUCT_DEFINITION_FORMATION('',$,#650); +#646=PRODUCT_RELATED_PRODUCT_CATEGORY('link5-6 v2','link5-6 v2',(#650)); +#647=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#648); +#648=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#649=PRODUCT_CONTEXT('part definition',#648,'mechanical'); +#650=PRODUCT('link5-6','link5-6 v2',$,(#649)); +#651=PRESENTATION_STYLE_ASSIGNMENT((#653)); +#652=PRESENTATION_STYLE_ASSIGNMENT((#654)); +#653=SURFACE_STYLE_USAGE(.BOTH.,#655); +#654=SURFACE_STYLE_USAGE(.BOTH.,#656); +#655=SURFACE_SIDE_STYLE('',(#657)); +#656=SURFACE_SIDE_STYLE('',(#658)); +#657=SURFACE_STYLE_FILL_AREA(#659); +#658=SURFACE_STYLE_FILL_AREA(#660); +#659=FILL_AREA_STYLE('Steel - Satin',(#661)); +#660=FILL_AREA_STYLE('Aluminum - Satin',(#662)); +#661=FILL_AREA_STYLE_COLOUR('Steel - Satin',#663); +#662=FILL_AREA_STYLE_COLOUR('Aluminum - Satin',#664); +#663=COLOUR_RGB('Steel - Satin',0.627450980392157,0.627450980392157,0.627450980392157); +#664=COLOUR_RGB('Aluminum - Satin',0.96078431372549,0.96078431372549,0.964705882352941); +ENDSEC; +END-ISO-10303-21; diff --git a/hardware/follower_STLs/dm-adapter_v0.2.0.stl b/hardware/follower_STLs/dm-adapter_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..855608b293a549dc854c3e56305298ac2607028a --- /dev/null +++ b/hardware/follower_STLs/dm-adapter_v0.2.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5624c4f26ad852a10f887b66c3959c0950498f0a72a459e3d0ea21f0b111d06a +size 124984 diff --git a/hardware/follower_STLs/dm-idler_v0.2.0.stl b/hardware/follower_STLs/dm-idler_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..c3be3dbf7dd219bd427d3a4b6e0db19bed2cd0b9 --- /dev/null +++ b/hardware/follower_STLs/dm-idler_v0.2.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c8943c9aeacf2aab129dbfda3524eb9f3a80c0c36ef330a8d5b8f617e702efa7 +size 121184 diff --git a/hardware/follower_STLs/dm-shaft-extension_v0.2.0.stl b/hardware/follower_STLs/dm-shaft-extension_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..62533528e2657ab5db3298572ccc53e2096bcb57 Binary files /dev/null and b/hardware/follower_STLs/dm-shaft-extension_v0.2.0.stl differ diff --git a/hardware/follower_STLs/joint5-cable-cover_v0.2.0.stl b/hardware/follower_STLs/joint5-cable-cover_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..db9124bb950d3ccbd727f58a2ff43c994751642c Binary files /dev/null and b/hardware/follower_STLs/joint5-cable-cover_v0.2.0.stl differ diff --git a/hardware/follower_STLs/like1-2-rest_v0.2.0.stl b/hardware/follower_STLs/like1-2-rest_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..2d15e11186bcf99a4048b1480aad8f9fa2b97237 Binary files /dev/null and b/hardware/follower_STLs/like1-2-rest_v0.2.0.stl differ diff --git a/hardware/follower_STLs/link2-3-frame_v0.2.0.stl b/hardware/follower_STLs/link2-3-frame_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..90978fecd547d0eb0b4ff4db23f1fdf29f534c1e --- /dev/null +++ b/hardware/follower_STLs/link2-3-frame_v0.2.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c8a40c51fcab8a20d40a4bd6758cf16a7d5000f3d81a76a4ca5e8f60a9e0bbfa +size 212184 diff --git a/hardware/follower_STLs/link3-4-frame_v0.2.0.stl b/hardware/follower_STLs/link3-4-frame_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..ab73f0c393c63759bc1f6f11f4d4cdff2b76ba00 --- /dev/null +++ b/hardware/follower_STLs/link3-4-frame_v0.2.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:235f18a25360ae49b89a650406de3b5ee3f7e4476a9b365fa7bb63f9c861342a +size 169484 diff --git a/hardware/follower_STLs/link5-6-rest_v0.2.0.stl b/hardware/follower_STLs/link5-6-rest_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..39fa31217d7a3cd7c2d7f6e9afd8742dcfb042b6 Binary files /dev/null and b/hardware/follower_STLs/link5-6-rest_v0.2.0.stl differ diff --git a/hardware/follower_STLs/link5-6-spacer_v0.2.0.stl b/hardware/follower_STLs/link5-6-spacer_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..d9617a5dec34249f38434753220d437523c55087 Binary files /dev/null and b/hardware/follower_STLs/link5-6-spacer_v0.2.0.stl differ diff --git a/hardware/follower_gripper_STLs/camera-shell_v0.2.0.stl b/hardware/follower_gripper_STLs/camera-shell_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..83ea161e2181838804003f7f3015ea744824a420 --- /dev/null +++ b/hardware/follower_gripper_STLs/camera-shell_v0.2.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f6cfef975c9ecf1049b1ff187ce633d571e3ee3027ab2c21d0bad98d09ce645b +size 152184 diff --git a/hardware/follower_gripper_STLs/d405-holder_v0.1.0.stl b/hardware/follower_gripper_STLs/d405-holder_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..9f29333c371d3289e2e4f31f4df563a59db431da --- /dev/null +++ b/hardware/follower_gripper_STLs/d405-holder_v0.1.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:136ceb501401f97699785f1c14e74accb7f620c58cd5c26cddf01645c951d33a +size 140184 diff --git a/hardware/follower_gripper_STLs/finger-holder_v0.2.0.stl b/hardware/follower_gripper_STLs/finger-holder_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..0a581a1470fb6711b5c23b17e67d31f89b51f856 Binary files /dev/null and b/hardware/follower_gripper_STLs/finger-holder_v0.2.0.stl differ diff --git a/hardware/follower_gripper_STLs/finger_v0.2.0.stl b/hardware/follower_gripper_STLs/finger_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..2614934bd5cb9ac48200e1f93fcafda95c02d613 Binary files /dev/null and b/hardware/follower_gripper_STLs/finger_v0.2.0.stl differ diff --git a/hardware/follower_gripper_STLs/gear-rack_v0.1.0.stl b/hardware/follower_gripper_STLs/gear-rack_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..6d49f4d253b9e42981e7ff110eb1a8c394e8d862 --- /dev/null +++ b/hardware/follower_gripper_STLs/gear-rack_v0.1.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a7f45a1c7ea891f88bffb38fddcda85b2d6fb2cbccda0b47fc84416fa695b539 +size 133484 diff --git a/hardware/follower_gripper_STLs/gear-shaft_v0.1.0.stl b/hardware/follower_gripper_STLs/gear-shaft_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..436c6aad6860d72cfc112c0fd497b46814b02e18 --- /dev/null +++ b/hardware/follower_gripper_STLs/gear-shaft_v0.1.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:aee32bffe1d05866b3cda19883155d9389087b0b29c8a54a72a44a4370ad2623 +size 300684 diff --git a/hardware/follower_gripper_STLs/link6-7-1_v0.2.0.stl b/hardware/follower_gripper_STLs/link6-7-1_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..eb4825e647a8db54deab383d88e2c8fcebf2b89a --- /dev/null +++ b/hardware/follower_gripper_STLs/link6-7-1_v0.2.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9849f4214e3f97ba5eea5ba02032ee9d6dfd790559665240bde7108feae949cc +size 212484 diff --git a/hardware/follower_gripper_STLs/link6-7-2_v0.2.0.stl b/hardware/follower_gripper_STLs/link6-7-2_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..c173f416be3ed8dd093e316fe035504a41bb8721 --- /dev/null +++ b/hardware/follower_gripper_STLs/link6-7-2_v0.2.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:abc440a7cc31f7f76e2e0cced95ebff76f5563cb8553f4de2090f2f33f1d3751 +size 198084 diff --git a/hardware/follower_gripper_STLs/soft-finger-holder_v0.2.0.stl b/hardware/follower_gripper_STLs/soft-finger-holder_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..31030bc466c4d88326108e1c78e49cfc3ef3c40e Binary files /dev/null and b/hardware/follower_gripper_STLs/soft-finger-holder_v0.2.0.stl differ diff --git a/hardware/follower_gripper_STLs/soft-finger_v0.2.0.stl b/hardware/follower_gripper_STLs/soft-finger_v0.2.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..d0350f029f13c57eff4e53f06f6810d2021209f7 Binary files /dev/null and b/hardware/follower_gripper_STLs/soft-finger_v0.2.0.stl differ diff --git a/hardware/leader_STLs/gello_handle_45deg.stl b/hardware/leader_STLs/gello_handle_45deg.stl new file mode 100644 index 0000000000000000000000000000000000000000..2b49663ce13f5251fd29850c55f23b448414fe75 --- /dev/null +++ b/hardware/leader_STLs/gello_handle_45deg.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:6f5c810aaa9ea0432532322e72e51c5faab949bef175a0130b2b4c96ac76ac50 +size 1102084 diff --git a/hardware/leader_STLs/gello_trigger.stl b/hardware/leader_STLs/gello_trigger.stl new file mode 100644 index 0000000000000000000000000000000000000000..76d94d379e07d6385f4418356684739174caf754 --- /dev/null +++ b/hardware/leader_STLs/gello_trigger.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:711d2bf0a499948efabd2dbcb39703532ac59f114965af1b14ec97efca52360f +size 159484 diff --git a/hardware/leader_STLs/leader.3mf b/hardware/leader_STLs/leader.3mf new file mode 100644 index 0000000000000000000000000000000000000000..7960a92e6d4548dd96d90a4853272e8fb7880fce --- /dev/null +++ b/hardware/leader_STLs/leader.3mf @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c073d6d119edfe6fe81b62006d18ef0113219571c602c3b2ba1b571b61bb15dd +size 512788 diff --git a/hardware/leader_STLs/link0-1_v0.1.0.stl b/hardware/leader_STLs/link0-1_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..188f0dec21b2009016fad1e1178a8591a07d89f5 --- /dev/null +++ b/hardware/leader_STLs/link0-1_v0.1.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b85f02e287827b17f5f392ecaaf4564f8598d7f2942c6db59f3808244427cef4 +size 131684 diff --git a/hardware/leader_STLs/link1-2_v0.1.0.stl b/hardware/leader_STLs/link1-2_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..c3c6be8307feb4565a3af24d2cfffee70d8c123b --- /dev/null +++ b/hardware/leader_STLs/link1-2_v0.1.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e2b313b350d65e6f6c2c33bf0f098a84b063c14020074a32782aa1d27316b5f2 +size 199384 diff --git a/hardware/leader_STLs/link2-3_v0.1.0.stl b/hardware/leader_STLs/link2-3_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..cc90954f2eae816d37bc47c12347edbd68b5416b Binary files /dev/null and b/hardware/leader_STLs/link2-3_v0.1.0.stl differ diff --git a/hardware/leader_STLs/link3-4_v0.1.0.stl b/hardware/leader_STLs/link3-4_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..a9935ebb78f783521322c150e150c1d8fe68e281 Binary files /dev/null and b/hardware/leader_STLs/link3-4_v0.1.0.stl differ diff --git a/hardware/leader_STLs/link4-5-flipped_v0.1.0.stl b/hardware/leader_STLs/link4-5-flipped_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..0675b5c4a80a9c0b6c0cfaa81629f6a1e98634c5 --- /dev/null +++ b/hardware/leader_STLs/link4-5-flipped_v0.1.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:6f9c94bbd29ac77ef91323d6664d513dadc9d65388aae54c7e0e44101d014309 +size 113384 diff --git a/hardware/leader_STLs/link4-5_v0.1.0.stl b/hardware/leader_STLs/link4-5_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..b5dd10081553eafadd7ade7d0a5c7e577ce05601 --- /dev/null +++ b/hardware/leader_STLs/link4-5_v0.1.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9fd1e9349c085a7593ffb32ac24138d9335d1a437f748632430112b2f7aa450a +size 113384 diff --git a/hardware/leader_STLs/link5-6-1_v0.1.0.stl b/hardware/leader_STLs/link5-6-1_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..c559e02e5c5e733cad7ccf8fafd4dc7a86a28f84 --- /dev/null +++ b/hardware/leader_STLs/link5-6-1_v0.1.0.stl @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b1bddc5de515b1aaab7efa7c187128d17119a9c1857e0f92f4ff0b090891a56d +size 126784 diff --git a/hardware/leader_STLs/link5-6-2_v0.1.0.stl b/hardware/leader_STLs/link5-6-2_v0.1.0.stl new file mode 100644 index 0000000000000000000000000000000000000000..eace9437c0c58f6962aebb70129679bc0e8e3176 Binary files /dev/null and b/hardware/leader_STLs/link5-6-2_v0.1.0.stl differ diff --git a/obs.py b/obs.py new file mode 100644 index 0000000000000000000000000000000000000000..0d07fd6ae36775e8756eaaf64c744653cbdd021f --- /dev/null +++ b/obs.py @@ -0,0 +1,24 @@ +from trlc_dk1.follower import DK1Follower, DK1FollowerConfig +from lerobot.cameras.opencv import OpenCVCameraConfig + +# Initialize the robot +config = DK1FollowerConfig( + right_arm_port="/dev/ttyACM0", + left_arm_port="/dev/ttyACM1", + joint_velocity_scaling=1.0, + cameras={ + "base_0": OpenCVCameraConfig(index_or_path=8, width=640, height=360, fps=30), + "left_wrist": OpenCVCameraConfig(index_or_path=6, width=640, height=360, fps=30), + "right_wrist": OpenCVCameraConfig(index_or_path=4, width=640, height=360, fps=30), + } +) +robot = DK1Follower(config) + +# Get an observation and print its structure +obs = robot.get_observation() + +print(type(obs)) +print(obs.keys()) + +import pprint +pprint.pprint(obs) \ No newline at end of file diff --git a/outputs/captured_images/media/demo.gif b/outputs/captured_images/media/demo.gif new file mode 100644 index 0000000000000000000000000000000000000000..0dbb90b246ced6f7ae4183f7f5a35fc8d54b12c6 --- /dev/null +++ b/outputs/captured_images/media/demo.gif @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f9fe2b99ecf0d9dae7cb22f9c1198301a378439a84509af09964974a12337482 +size 3186085 diff --git a/outputs/captured_images/media/follower_cad.png b/outputs/captured_images/media/follower_cad.png new file mode 100644 index 0000000000000000000000000000000000000000..42a23ddabcfd4e57c9a2b7858f95b62a6fa042ba --- /dev/null +++ b/outputs/captured_images/media/follower_cad.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a6d7ada5bcddfb16d414d8036a57732a4f3f8c504aa66754bbad0866546b3447 +size 766042 diff --git a/outputs/captured_images/media/leader_cad.png b/outputs/captured_images/media/leader_cad.png new file mode 100644 index 0000000000000000000000000000000000000000..59ceaa6933578f44656ed2c74ffacb9dab9328e4 --- /dev/null +++ b/outputs/captured_images/media/leader_cad.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7d191ac9a24ace4f442401f70b820ed4e14086a5845e1358fa9d1ca3398f4189 +size 686282 diff --git a/outputs/captured_images/media/xray.jpg b/outputs/captured_images/media/xray.jpg new file mode 100644 index 0000000000000000000000000000000000000000..a7d7d986b00c1abc2bec21ad7ac3374a03731960 --- /dev/null +++ b/outputs/captured_images/media/xray.jpg @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7a86d3e8235654927aab29e5ff0ec813e09e30e912ab017eab045a17fa583ae1 +size 403565 diff --git a/outputs/captured_images/opencv__dev_video0.png b/outputs/captured_images/opencv__dev_video0.png new file mode 100644 index 0000000000000000000000000000000000000000..7844acddfdc6929eccac432cd5221b9a12078d39 --- /dev/null +++ b/outputs/captured_images/opencv__dev_video0.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:10674d0c163841d0a997a3558a180e610882d06848e79f82212dc8614f62348f +size 369638 diff --git a/outputs/captured_images/opencv__dev_video2.png b/outputs/captured_images/opencv__dev_video2.png new file mode 100644 index 0000000000000000000000000000000000000000..2c12f0d22a16c3903261c198d4d2bf1be12ccd4f --- /dev/null +++ b/outputs/captured_images/opencv__dev_video2.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:85f46f09c7030772afdd7a5345a9bd6f7c8cd1977ca1abe28f52f519689071dc +size 46825 diff --git a/outputs/captured_images/opencv__dev_video4.png b/outputs/captured_images/opencv__dev_video4.png new file mode 100644 index 0000000000000000000000000000000000000000..8c2df5bab38d2855cc6f0a3581134a5e2a675fd2 --- /dev/null +++ b/outputs/captured_images/opencv__dev_video4.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e439e14e969fbab335913c8826afd51c107c63b247f8081837a725a41434dc5f +size 176262 diff --git a/outputs/captured_images/opencv__dev_video6.png b/outputs/captured_images/opencv__dev_video6.png new file mode 100644 index 0000000000000000000000000000000000000000..73b3e941f931d8b291f3f6bd567c45a4bff4cc3d --- /dev/null +++ b/outputs/captured_images/opencv__dev_video6.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8eead68b3a6bc45b4370679407dc50edc0097341e5612ac41b328db1c93e4f14 +size 181008 diff --git a/outputs/captured_images/opencv__dev_video8.png b/outputs/captured_images/opencv__dev_video8.png new file mode 100644 index 0000000000000000000000000000000000000000..84f8dadbd31d70ea09aa9c271e219a246cdf0ae2 --- /dev/null +++ b/outputs/captured_images/opencv__dev_video8.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5218716ea19af2701e5971b1774ba6a0103a99fc3363d024955b80d8c5c54419 +size 432802 diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 0000000000000000000000000000000000000000..99d34903d31a437ca86d2ef5ef140426e6004373 --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,27 @@ +[build-system] +requires = ["hatchling"] +build-backend = "hatchling.build" + +[project] +name = "trlc_dk1" +version = "0.1.0" +dependencies = [ + "numpy>=2.0.1", + "pyserial>=3.5", + "dynamixel-sdk>=3.7.31", + "lerobot@git+https://github.com/robot-learning-co/lerobot.git@trlc-dk1", +] + +authors = [ + {name = "Jannik Grothusen", email = "jannik@robot-learning.co"}, +] +maintainers = [ + {name = "Jannik Grothusen", email = "jannik@robot-learning.co"}, +] + +[project.urls] +Homepage = "https://www.robot-learning.co/" +Documentation = "https://www.docs.robot-learning.co/" + +[tool.hatch.metadata] +allow-direct-references = true \ No newline at end of file diff --git a/run_rtc.py b/run_rtc.py new file mode 100644 index 0000000000000000000000000000000000000000..6f4820221ecb2427875d6518e8025d1c0997502b --- /dev/null +++ b/run_rtc.py @@ -0,0 +1,340 @@ +#!/usr/bin/env python3 +""" +PI05 RTC Inference - With Action Logging +""" + +import torch +import time +import numpy as np +import threading +import traceback + +torch._dynamo.config.suppress_errors = True +torch._dynamo.config.disable = True + +from lerobot.policies.pi05.modeling_pi05 import PI05Policy +from lerobot.configs.types import RTCAttentionSchedule +from lerobot.policies.rtc.configuration_rtc import RTCConfig +from lerobot.policies.rtc.modeling_rtc import RTCProcessor +from trlc_dk1.follower import DK1Follower, DK1FollowerConfig +from lerobot.cameras.opencv import OpenCVCameraConfig +from transformers import AutoTokenizer + + +# ============================================================================= +# Configuration +# ============================================================================= + +MODEL_PATH = "qualiaadmin/81df74e6-274f-4f02-aaa7-c1f83c549832" +TOKENIZER_NAME = "google/paligemma-3b-pt-224" +TASK = "clean the table" + +CONTROL_FREQ = 50 +CHUNK_SIZE = 50 +EXECUTION_HORIZON = 20 + +# Tuned settings +USE_RTC = True +MAX_GUIDANCE_WEIGHT = 5.0 # Reduced from 10 +SMOOTH_ALPHA = 0.85 # More responsive + +# Robot +ROBOT_PORT = "/dev/ttyACM0" +TOP_CAMERA_INDEX = 6 +WRIST_CAMERA_INDEX = 4 + +# Normalization +STATE_MEAN = torch.tensor([0.1108, 0.8736, 0.7812, -0.3134, 0.0278, -0.0890, 0.2867]).cuda() +STATE_STD = torch.tensor([0.2484, 0.6667, 0.5777, 0.3697, 0.0903, 0.1300, 0.4132]).cuda() +ACTION_MEAN = torch.tensor([0.1110, 0.8739, 0.7815, -0.3132, 0.0280, -0.0888, 0.2853]).cuda() +ACTION_STD = torch.tensor([0.2519, 0.6752, 0.5838, 0.3747, 0.0924, 0.1315, 0.4204]).cuda() + + +# ============================================================================= +# Classes +# ============================================================================= + +class RTCActionQueue: + def __init__(self): + self.actions = [] + self.prev_chunk_normalized = None + self.lock = threading.Lock() + self.last_chunk_stats = None # For logging + + def remaining(self) -> int: + with self.lock: + return len(self.actions) + + def get_left_over_for_rtc(self): + with self.lock: + if self.prev_chunk_normalized is None: + return None + return self.prev_chunk_normalized.clone() + + def set_new_chunk(self, actions_tensor: torch.Tensor, inference_delay: int): + with self.lock: + self.prev_chunk_normalized = actions_tensor[:, inference_delay:, :].detach().clone() + actions = actions_tensor[0] if actions_tensor.dim() == 3 else actions_tensor + actions = actions * ACTION_STD + ACTION_MEAN + actions_np = actions.detach().cpu().numpy()[inference_delay:] + + # Compute chunk stats + if len(actions_np) > 1: + deltas = np.diff(actions_np, axis=0) + self.last_chunk_stats = { + 'mean_delta': np.mean(np.abs(deltas)), + 'max_delta': np.max(np.abs(deltas)), + 'range': np.ptp(actions_np, axis=0), # Peak-to-peak per joint + } + + self.actions = list(actions_np) + + def get(self): + with self.lock: + return self.actions.pop(0) if self.actions else None + + def get_chunk_stats(self): + with self.lock: + return self.last_chunk_stats + + +class ActionSmoother: + def __init__(self, alpha: float): + self.alpha = alpha + self.prev = None + + def __call__(self, action: np.ndarray) -> np.ndarray: + if self.alpha >= 1.0 or self.prev is None: + self.prev = action.copy() + return action + smoothed = self.alpha * action + (1 - self.alpha) * self.prev + self.prev = smoothed.copy() + return smoothed + + +def format_observation(raw_obs: dict, tokenizer) -> dict: + state = torch.tensor([ + raw_obs["joint_1.pos"], raw_obs["joint_2.pos"], raw_obs["joint_3.pos"], + raw_obs["joint_4.pos"], raw_obs["joint_5.pos"], raw_obs["joint_6.pos"], + raw_obs["gripper.pos"], + ], dtype=torch.float32).cuda() + state = ((state - STATE_MEAN) / STATE_STD).unsqueeze(0) + + top = raw_obs["top"] + wrist = raw_obs["wrist"] + if not isinstance(top, torch.Tensor): + top = torch.from_numpy(top).permute(2, 0, 1).float() / 255.0 + wrist = torch.from_numpy(wrist).permute(2, 0, 1).float() / 255.0 + + tokens = tokenizer(TASK, return_tensors="pt", padding="max_length", max_length=48, truncation=True) + + return { + "observation.images.top": top.unsqueeze(0).cuda(), + "observation.images.wrist": wrist.unsqueeze(0).cuda(), + "observation.state": state, + "observation.language.tokens": tokens["input_ids"].cuda(), + "observation.language.attention_mask": tokens["attention_mask"].bool().cuda(), + } + + +def action_to_dict(action: np.ndarray) -> dict: + return {f"joint_{i}.pos": float(action[i-1]) for i in range(1, 7)} | {"gripper.pos": float(action[6])} + + +# ============================================================================= +# Main +# ============================================================================= + +def main(): + print("=" * 60) + print("PI05 RTC Inference - Action Analysis Mode") + print("=" * 60) + print(f"\nUSE_RTC={USE_RTC}, GUIDANCE={MAX_GUIDANCE_WEIGHT}, SMOOTH={SMOOTH_ALPHA}\n") + + # Setup + rtc_config = RTCConfig( + enabled=USE_RTC, + execution_horizon=EXECUTION_HORIZON, + max_guidance_weight=MAX_GUIDANCE_WEIGHT, + prefix_attention_schedule=RTCAttentionSchedule.EXP, + ) + + print("Loading model...") + policy = PI05Policy.from_pretrained(MODEL_PATH, device="cuda") + policy.eval() + + if USE_RTC: + policy.config.rtc_config = rtc_config + rtc_processor = RTCProcessor(rtc_config) + policy.rtc_processor = rtc_processor + if hasattr(policy, 'model'): + policy.model.config.rtc_config = rtc_config + policy.model.rtc_processor = rtc_processor + + tokenizer = AutoTokenizer.from_pretrained(TOKENIZER_NAME) + + print("Connecting to robot...") + robot_config = DK1FollowerConfig( + port=ROBOT_PORT, + cameras={ + "top": OpenCVCameraConfig(index_or_path=TOP_CAMERA_INDEX, width=640, height=360, fps=30), + "wrist": OpenCVCameraConfig(index_or_path=WRIST_CAMERA_INDEX, width=640, height=360, fps=30), + }, + ) + robot = DK1Follower(robot_config) + robot.connect() + print("Ready!\n") + + # Analyze initial state + raw_obs = robot.get_observation() + current_pos = np.array([raw_obs[f"joint_{i}.pos"] for i in range(1, 7)] + [raw_obs["gripper.pos"]]) + + print("=" * 40) + print("POSITION ANALYSIS") + print("=" * 40) + print(f"Current: {np.round(current_pos, 3)}") + print(f"Mean: {np.round(STATE_MEAN.cpu().numpy(), 3)}") + print(f"Delta: {np.round(current_pos - STATE_MEAN.cpu().numpy(), 3)}") + print() + + # Test inference and analyze + obs = format_observation(raw_obs, tokenizer) + with torch.enable_grad(): + action_tensor = policy.predict_action_chunk(obs) + + actions_np = (action_tensor[0] * ACTION_STD + ACTION_MEAN).detach().cpu().numpy() + + print("=" * 40) + print("ACTION CHUNK ANALYSIS") + print("=" * 40) + print(f"First action: {np.round(actions_np[0], 3)}") + print(f"Last action: {np.round(actions_np[-1], 3)}") + print(f"Chunk range: {np.round(np.ptp(actions_np, axis=0), 3)}") + print(f"Mean step size: {np.round(np.mean(np.abs(np.diff(actions_np, axis=0)), axis=0), 4)}") + print() + + # Show trajectory + print("Action trajectory (joint 1,2,3 at steps 0,10,20,30,40,49):") + for i in [0, 10, 20, 30, 40, 49]: + print(f" [{i:2d}] {np.round(actions_np[i, :3], 3)}") + print() + + input("Press Enter to start execution...") + + # Shared state + action_queue = RTCActionQueue() + smoother = ActionSmoother(SMOOTH_ALPHA) + latest_obs = None + obs_lock = threading.Lock() + running = True + first_chunk_ready = threading.Event() + inference_times = [] + + def inference_loop(): + nonlocal running + + while running: + with obs_lock: + obs = latest_obs + if obs is None: + time.sleep(0.01) + continue + + try: + formatted = format_observation(obs, tokenizer) + prev_actions = action_queue.get_left_over_for_rtc() if USE_RTC else None + + if inference_times: + delay = int(np.ceil(np.mean(inference_times[-10:]) * CONTROL_FREQ)) + delay = max(1, min(delay, CHUNK_SIZE - EXECUTION_HORIZON - 1)) + else: + delay = 10 + + start = time.time() + with torch.enable_grad(): + actions = policy.predict_action_chunk( + formatted, + inference_delay=delay if USE_RTC else 0, + prev_chunk_left_over=prev_actions, + ) + elapsed = time.time() - start + inference_times.append(elapsed) + + action_queue.set_new_chunk(actions, delay) + first_chunk_ready.set() + + # Log with chunk stats + stats = action_queue.get_chunk_stats() + if stats: + print(f"Inference: {elapsed*1000:.0f}ms | queue: {action_queue.remaining()} | " + f"mean_delta: {stats['mean_delta']:.4f} | max_delta: {stats['max_delta']:.4f}") + + while running and action_queue.remaining() > EXECUTION_HORIZON: + time.sleep(0.005) + + except Exception as e: + print(f"[ERROR] {e}") + traceback.print_exc() + time.sleep(1) + + threading.Thread(target=inference_loop, daemon=True).start() + + raw_obs = robot.get_observation() + with obs_lock: + latest_obs = raw_obs + + first_chunk_ready.wait(timeout=60) + print("\nRunning!\n") + + step = 0 + loop_period = 1.0 / CONTROL_FREQ + + # Track executed actions for analysis + executed_actions = [] + + try: + while running: + t0 = time.time() + + raw_obs = robot.get_observation() + with obs_lock: + latest_obs = raw_obs + + action = action_queue.get() + if action is not None: + action = smoother(action) + robot.send_action(action_to_dict(action)) + executed_actions.append(action.copy()) + step += 1 + + if step % 200 == 0: + # Analyze recent execution + recent = np.array(executed_actions[-200:]) + total_movement = np.sum(np.abs(np.diff(recent, axis=0))) + print(f"Step {step} | Total movement (last 200): {total_movement:.2f} rad") + + dt = time.time() - t0 + if dt < loop_period: + time.sleep(loop_period - dt) + + except KeyboardInterrupt: + print("\n\nStopping...") + + # Final analysis + if len(executed_actions) > 100: + all_actions = np.array(executed_actions) + print("\n" + "=" * 40) + print("EXECUTION SUMMARY") + print("=" * 40) + print(f"Total steps: {len(executed_actions)}") + print(f"Position range: {np.round(np.ptp(all_actions, axis=0), 3)}") + print(f"Mean step size: {np.round(np.mean(np.abs(np.diff(all_actions, axis=0)), axis=0), 4)}") + print(f"Total movement: {np.sum(np.abs(np.diff(all_actions, axis=0))):.2f} rad") + finally: + running = False + robot.disconnect() + print("Done!") + + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/src/trlc_dk1/__init__.py b/src/trlc_dk1/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 diff --git a/src/trlc_dk1/bi_follower.py b/src/trlc_dk1/bi_follower.py new file mode 100644 index 0000000000000000000000000000000000000000..a470732f9877f2849e624ab36726fa675f7b1bfa --- /dev/null +++ b/src/trlc_dk1/bi_follower.py @@ -0,0 +1,157 @@ +# Copyright 2025 The Robot Learning Company UG (haftungsbeschränkt). All rights reserved. +# +# 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 dataclasses import dataclass, field +from functools import cached_property +import time +import logging +from typing import Any + +from lerobot.cameras import CameraConfig +from lerobot.cameras.utils import make_cameras_from_configs +from lerobot.robots import Robot, RobotConfig + +from trlc_dk1.motors.DM_Control_Python.DM_CAN import * +from trlc_dk1.follower import DK1Follower, DK1FollowerConfig + +logger = logging.getLogger(__name__) +logger.setLevel(logging.DEBUG) + + +def map_range(x: float, in_min: float, in_max: float, out_min: float, out_max: float) -> float: + return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min + + +@RobotConfig.register_subclass("bi_dk1_follower") +@dataclass +class BiDK1FollowerConfig(RobotConfig): + left_arm_port: str + right_arm_port: str + disable_torque_on_disconnect: bool = False + joint_velocity_scaling: float = 0.2 + max_gripper_torque: float = 1.0 # Nm (/0.00875m spur gear radius = 114N gripper force) + cameras: dict[str, CameraConfig] = field(default_factory=dict) + + +class BiDK1Follower(Robot): + """ + Bimanual TRLC-DK1 Follower Arm designed by The Robot Learning Company. + """ + + config_class = BiDK1FollowerConfig + name = "bi_dk1_follower" + + def __init__(self, config: BiDK1FollowerConfig): + super().__init__(config) + + self.config = config + + left_arm_config = DK1FollowerConfig( + port=self.config.left_arm_port, + disable_torque_on_disconnect=self.config.disable_torque_on_disconnect, + joint_velocity_scaling=self.config.joint_velocity_scaling, + max_gripper_torque=self.config.max_gripper_torque, + ) + right_arm_config = DK1FollowerConfig( + port=self.config.right_arm_port, + disable_torque_on_disconnect=self.config.disable_torque_on_disconnect, + joint_velocity_scaling=self.config.joint_velocity_scaling, + max_gripper_torque=self.config.max_gripper_torque, + ) + + self.left_arm = DK1Follower(left_arm_config) + self.right_arm = DK1Follower(right_arm_config) + self.cameras = make_cameras_from_configs(config.cameras) + + @property + def _motors_ft(self) -> dict[str, type]: + return {f"left_{motor}.pos": float for motor in self.left_arm.motors} | { + f"right_{motor}.pos": float for motor in self.right_arm.motors + } + + @property + def _cameras_ft(self) -> dict[str, tuple]: + return { + cam: (self.config.cameras[cam].height, self.config.cameras[cam].width, 3) for cam in self.cameras + } + + @cached_property + def observation_features(self) -> dict[str, type | tuple]: + return {**self._motors_ft, **self._cameras_ft} + + @cached_property + def action_features(self) -> dict[str, type]: + return self._motors_ft + + @property + def is_connected(self) -> bool: + return self.left_arm.is_connected and self.right_arm.is_connected and all(cam.is_connected for cam in self.cameras.values()) + + def connect(self) -> None: + self.left_arm.connect() + self.right_arm.connect() + + for cam in self.cameras.values(): + cam.connect() + + @property + def is_calibrated(self) -> bool: + return True + + def calibrate(self) -> None: + pass + + def configure(self) -> None: + self.left_arm.configure() + self.right_arm.configure() + + def get_observation(self) -> dict[str, Any]: + obs_dict = {} + + left_obs = self.left_arm.get_observation() + obs_dict.update({f"left_{key}": value for key, value in left_obs.items()}) + + right_obs = self.right_arm.get_observation() + obs_dict.update({f"right_{key}": value for key, value in right_obs.items()}) + + for cam_key, cam in self.cameras.items(): + start = time.perf_counter() + obs_dict[cam_key] = cam.async_read() + dt_ms = (time.perf_counter() - start) * 1e3 + logger.debug(f"{self} read {cam_key}: {dt_ms:.1f}ms") + + return obs_dict + + def send_action(self, action: dict[str, Any]) -> dict[str, Any]: + left_action = { + key.removeprefix("left_"): value for key, value in action.items() if key.startswith("left_") + } + right_action = { + key.removeprefix("right_"): value for key, value in action.items() if key.startswith("right_") + } + + send_action_left = self.left_arm.send_action(left_action) + send_action_right = self.right_arm.send_action(right_action) + + prefixed_send_action_left = {f"left_{key}": value for key, value in send_action_left.items()} + prefixed_send_action_right = {f"right_{key}": value for key, value in send_action_right.items()} + + return {**prefixed_send_action_left, **prefixed_send_action_right} + + def disconnect(self): + self.left_arm.disconnect() + self.right_arm.disconnect() + + for cam in self.cameras.values(): + cam.disconnect() diff --git a/src/trlc_dk1/bi_leader.py b/src/trlc_dk1/bi_leader.py new file mode 100644 index 0000000000000000000000000000000000000000..56620dca207d77c3dee606366011532e417c697d --- /dev/null +++ b/src/trlc_dk1/bi_leader.py @@ -0,0 +1,105 @@ +# Copyright 2025 The Robot Learning Company UG (haftungsbeschränkt). All rights reserved. +# +# 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 dataclasses import dataclass +import logging +from lerobot.teleoperators.teleoperator import Teleoperator, TeleoperatorConfig + +from trlc_dk1.leader import DK1Leader, DK1LeaderConfig + +logger = logging.getLogger(__name__) + + +@TeleoperatorConfig.register_subclass("bi_dk1_leader") +@dataclass +class BiDK1LeaderConfig(TeleoperatorConfig): + left_arm_port: str + right_arm_port: str + gripper_open_pos: int = 2280 + gripper_closed_pos: int = 1670 + + +class BiDK1Leader(Teleoperator): + config_class = BiDK1LeaderConfig + name = "bi_dk1_leader" + + def __init__(self, config: BiDK1LeaderConfig): + super().__init__(config) + self.config = config + + left_arm_config = DK1LeaderConfig( + port=self.config.left_arm_port, + gripper_open_pos=self.config.gripper_open_pos, + gripper_closed_pos=self.config.gripper_closed_pos, + ) + right_arm_config = DK1LeaderConfig( + port=self.config.right_arm_port, + gripper_open_pos=self.config.gripper_open_pos, + gripper_closed_pos=self.config.gripper_closed_pos, + ) + + self.left_arm = DK1Leader(left_arm_config) + self.right_arm = DK1Leader(right_arm_config) + + @property + def action_features(self) -> dict[str, type]: + return {f"left_{motor}.pos": float for motor in self.left_arm.bus.motors} | { + f"right_{motor}.pos": float for motor in self.right_arm.bus.motors + } + + @property + def feedback_features(self) -> dict[str, type]: + return {} + + @property + def is_connected(self) -> bool: + return self.left_arm.is_connected and self.right_arm.is_connected + + def connect(self, calibrate: bool = False) -> None: + self.left_arm.connect() + self.right_arm.connect() + + @property + def is_calibrated(self) -> bool: + return True + + def calibrate(self) -> None: + pass + + def configure(self) -> None: + self.left_arm.configure() + self.right_arm.configure() + + def setup_motors(self) -> None: + self.left_arm.setup_motors() + self.right_arm.setup_motors() + + def get_action(self) -> dict[str, float]: + action_dict = {} + + left_action = self.left_arm.get_action() + action_dict.update({f"left_{key}": value for key, value in left_action.items()}) + + right_action = self.right_arm.get_action() + action_dict.update({f"right_{key}": value for key, value in right_action.items()}) + + return action_dict + + def send_feedback(self, feedback: dict[str, float]) -> None: + # TODO(rcadene, aliberts): Implement force feedback + raise NotImplementedError + + def disconnect(self) -> None: + self.left_arm.disconnect() + self.right_arm.disconnect() \ No newline at end of file diff --git a/src/trlc_dk1/follower.py b/src/trlc_dk1/follower.py new file mode 100644 index 0000000000000000000000000000000000000000..2a67589677467badb9c2b8a3c9baa2ce369fb1d9 --- /dev/null +++ b/src/trlc_dk1/follower.py @@ -0,0 +1,246 @@ +# Copyright 2025 The Robot Learning Company UG (haftungsbeschränkt). All rights reserved. +# +# 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 dataclasses import dataclass, field +from functools import cached_property +import serial +import time +import logging +from typing import Any + +from lerobot.cameras import CameraConfig +from lerobot.cameras.utils import make_cameras_from_configs +from lerobot.robots import Robot, RobotConfig +from lerobot.robots.utils import ensure_safe_goal_position +from lerobot.utils.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError + +from trlc_dk1.motors.DM_Control_Python.DM_CAN import * + +logger = logging.getLogger(__name__) + + +def map_range(x: float, in_min: float, in_max: float, out_min: float, out_max: float) -> float: + return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min + + +@RobotConfig.register_subclass("dk1_follower") +@dataclass +class DK1FollowerConfig(RobotConfig): + port: str + disable_torque_on_disconnect: bool = False + joint_velocity_scaling: float = 0.2 + max_gripper_torque: float = 1.0 # Nm (/0.00875m spur gear radius = 114N gripper force) + cameras: dict[str, CameraConfig] = field(default_factory=dict) + + +class DK1Follower(Robot): + """ + TRLC-DK1 Follower Arm designed by The Robot Learning Company. + """ + + config_class = DK1FollowerConfig + name = "dk1_follower" + + def __init__(self, config: DK1FollowerConfig): + super().__init__(config) + + # Constants for EMIT control + self.DM4310_TORQUE_CONSTANT = 0.945 # Nm/A + self.EMIT_VELOCITY_SCALE = 100 # rad/s + self.EMIT_CURRENT_SCALE = 1000 # A + + self.JOINT_LIMITS = { + "joint_4": (-100/180*np.pi, 100/180*np.pi), + "joint_5": (-90/180*np.pi, 90/180*np.pi), + } + + self.DM4310_SPEED = 200/60*2*np.pi # rad/s (200 rpm | 20.94 rad/s) + self.DM4340_SPEED = 52.5/60*2*np.pi # rad/s (52.5 rpm | 5.49 rad/s) + + self.config = config + self.motors = { + "joint_1": Motor(DM_Motor_Type.DM4340, 0x01, 0x11), + "joint_2": Motor(DM_Motor_Type.DM4340, 0x02, 0x12), + "joint_3": Motor(DM_Motor_Type.DM4340, 0x03, 0x13), + "joint_4": Motor(DM_Motor_Type.DM4310, 0x04, 0x14), + "joint_5": Motor(DM_Motor_Type.DM4310, 0x05, 0x15), + "joint_6": Motor(DM_Motor_Type.DM4310, 0x06, 0x16), + "gripper": Motor(DM_Motor_Type.DM4310, 0x07, 0x17), + } + self.control = None + self.serial_device = None + self.bus_connected = False + + self.gripper_open_pos = 0.0 + self.gripper_closed_pos = -4.7 + + self.cameras = make_cameras_from_configs(config.cameras) + + @property + def _motors_ft(self) -> dict[str, type]: + return {f"{motor}.pos": float for motor in self.motors} + + @property + def _cameras_ft(self) -> dict[str, tuple]: + return { + cam: (self.config.cameras[cam].height, self.config.cameras[cam].width, 3) for cam in self.cameras + } + + @cached_property + def observation_features(self) -> dict[str, type | tuple]: + return {**self._motors_ft, **self._cameras_ft} + + @cached_property + def action_features(self) -> dict[str, type]: + return self._motors_ft + + @property + def is_connected(self) -> bool: + return self.bus_connected and all(cam.is_connected for cam in self.cameras.values()) + + def connect(self) -> None: + if self.is_connected: + raise DeviceAlreadyConnectedError(f"{self} already connected") + + self.serial_device = serial.Serial( + self.config.port, 921600, timeout=0.5) + time.sleep(0.5) + + self.control = MotorControl(self.serial_device) + self.bus_connected = True + self.configure() + + for cam in self.cameras.values(): + cam.connect() + + @property + def is_calibrated(self) -> bool: + return True + + def calibrate(self) -> None: + pass + + def configure(self) -> None: + + for key, motor in self.motors.items(): + self.control.addMotor(motor) + + for _ in range(3): + self.control.refresh_motor_status(motor) + time.sleep(0.01) + + if self.control.read_motor_param(motor, DM_variable.CTRL_MODE) is not None: + print(f"{key} ({motor.MotorType.name}) is connected.") + + self.control.switchControlMode(motor, Control_Type.POS_VEL) + self.control.enable(motor) + else: + raise Exception( + f"Unable to read from {key} ({motor.MotorType.name}).") + + for joint in ["joint_1", "joint_2", "joint_3"]: + self.control.change_motor_param(self.motors[joint], DM_variable.ACC, 10.0) + self.control.change_motor_param(self.motors[joint], DM_variable.DEC, -10.0) + self.control.change_motor_param(self.motors[joint], DM_variable.KP_APR, 200) + self.control.change_motor_param(self.motors[joint], DM_variable.KI_APR, 10) + + for joint in ["gripper"]: + self.control.change_motor_param( + self.motors[joint], DM_variable.KP_APR, 100) + + # Open gripper and set zero position + self.control.switchControlMode( + self.motors["gripper"], Control_Type.VEL) + self.control.control_Vel(self.motors["gripper"], 10.0) + while True: + self.control.refresh_motor_status(self.motors["gripper"]) + tau = self.motors["gripper"].getTorque() + if tau > 1.2: + self.control.control_Vel(self.motors["gripper"], 0.0) + self.control.disable(self.motors["gripper"]) + self.control.set_zero_position(self.motors["gripper"]) + time.sleep(0.2) + self.control.enable(self.motors["gripper"]) + break + time.sleep(0.01) + self.control.switchControlMode( + self.motors["gripper"], Control_Type.Torque_Pos) + + def get_observation(self) -> dict[str, Any]: + if not self.is_connected: + raise DeviceNotConnectedError(f"{self} is not connected.") + + # Read arm position + start = time.perf_counter() + + obs_dict = {} + for key, motor in self.motors.items(): + self.control.refresh_motor_status(motor) + if key == "gripper": + # Normalize gripper position between 1 (closed) and 0 (open) + obs_dict[f"{key}.pos"] = map_range( + motor.getPosition(), self.gripper_open_pos, self.gripper_closed_pos, 0.0, 1.0) + else: + obs_dict[f"{key}.pos"] = motor.getPosition() + + dt_ms = (time.perf_counter() - start) * 1e3 + logger.debug(f"{self} read state: {dt_ms:.1f}ms") + + # Capture images from cameras + for cam_key, cam in self.cameras.items(): + start = time.perf_counter() + obs_dict[cam_key] = cam.async_read() + dt_ms = (time.perf_counter() - start) * 1e3 + logger.debug(f"{self} read {cam_key}: {dt_ms:.1f}ms") + + return obs_dict + + def send_action(self, action: dict[str, Any]) -> dict[str, Any]: + if not self.is_connected: + raise DeviceNotConnectedError(f"{self} is not connected.") + + goal_pos = {key.removesuffix( + ".pos"): val for key, val in action.items() if key.endswith(".pos")} + + # Send goal position to the arm + for key, motor in self.motors.items(): + if key == "gripper": + self.control.refresh_motor_status(motor) + gripper_goal_pos_mapped = map_range(goal_pos[key], 0.0, 1.0, self.gripper_open_pos, self.gripper_closed_pos) + self.control.control_pos_force(motor, gripper_goal_pos_mapped, self.DM4310_SPEED*self.EMIT_VELOCITY_SCALE, + i_des=self.config.max_gripper_torque/self.DM4310_TORQUE_CONSTANT*self.EMIT_CURRENT_SCALE) + else: + if key in self.JOINT_LIMITS: + goal_pos[key] = np.clip(goal_pos[key], self.JOINT_LIMITS[key][0], self.JOINT_LIMITS[key][1]) + + self.control.control_Pos_Vel( + motor, goal_pos[key], self.config.joint_velocity_scaling*self.DM4340_SPEED) + + return {f"{motor}.pos": val for motor, val in goal_pos.items()} + + def disconnect(self): + if not self.is_connected: + raise DeviceNotConnectedError(f"{self} is not connected.") + + if self.config.disable_torque_on_disconnect: + for motor in self.motors.values(): + self.control.disable(motor) + else: + self.control.serial_.close() + self.bus_connected = False + + for cam in self.cameras.values(): + cam.disconnect() + + logger.info(f"{self} disconnected.") diff --git a/src/trlc_dk1/leader.py b/src/trlc_dk1/leader.py new file mode 100644 index 0000000000000000000000000000000000000000..fea4c8eede60a1ee8f13318dc6151de6d068cd97 --- /dev/null +++ b/src/trlc_dk1/leader.py @@ -0,0 +1,130 @@ +# Copyright 2025 The Robot Learning Company UG (haftungsbeschränkt). All rights reserved. +# +# 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 dataclasses import dataclass +import logging +import time +import numpy as np + +from lerobot.teleoperators.teleoperator import Teleoperator, TeleoperatorConfig +from lerobot.utils.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError +from lerobot.motors import Motor, MotorNormMode +from lerobot.motors.dynamixel import ( + DynamixelMotorsBus, + OperatingMode, +) + +logger = logging.getLogger(__name__) + + +@TeleoperatorConfig.register_subclass("dk1_leader") +@dataclass +class DK1LeaderConfig(TeleoperatorConfig): + port: str + gripper_open_pos: int = 2280 + gripper_closed_pos: int = 1670 + + +class DK1Leader(Teleoperator): + config_class = DK1LeaderConfig + name = "dk1_leader" + + def __init__(self, config: DK1LeaderConfig): + super().__init__(config) + self.config = config + self.bus = DynamixelMotorsBus( + port=self.config.port, + motors={ + "joint_1": Motor(1, "xl330-m288", MotorNormMode.DEGREES), + "joint_2": Motor(2, "xl330-m288", MotorNormMode.DEGREES), + "joint_3": Motor(3, "xl330-m077", MotorNormMode.DEGREES), + "joint_4": Motor(4, "xl330-m077", MotorNormMode.DEGREES), + "joint_5": Motor(5, "xl330-m288", MotorNormMode.DEGREES), + "joint_6": Motor(6, "xl330-m288", MotorNormMode.DEGREES), + "gripper": Motor(7, "xl330-m077", MotorNormMode.DEGREES), + }, + ) + + @property + def action_features(self) -> dict[str, type]: + return {f"{motor}.pos": float for motor in self.bus.motors} + + @property + def feedback_features(self) -> dict[str, type]: + return {} + + @property + def is_connected(self) -> bool: + return self.bus.is_connected + + def connect(self, calibrate: bool = False) -> None: + if self.is_connected: + raise DeviceAlreadyConnectedError(f"{self} already connected") + + self.bus.connect() + self.configure() + + logger.info(f"{self} connected.") + + @property + def is_calibrated(self) -> bool: + return True + + def calibrate(self) -> None: + pass + + def configure(self) -> None: + self.bus.disable_torque() + self.bus.configure_motors() + + # Enable torque and set to position to open + self.bus.write("Torque_Enable", "gripper", 0, normalize=False) + self.bus.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value, normalize=False) + self.bus.write("Current_Limit", "gripper", 100, normalize=False) + self.bus.write("Torque_Enable", "gripper", 1, normalize=False) + self.bus.write("Goal_Position", "gripper", self.config.gripper_open_pos, normalize=False) + + def setup_motors(self) -> None: + for motor in self.bus.motors: + input(f"Connect the controller board to the '{motor}' motor only and press enter.") + self.bus.setup_motor(motor) + print(f"'{motor}' motor id set to {self.bus.motors[motor].id}") + + def get_action(self) -> dict[str, float]: + if not self.is_connected: + raise DeviceNotConnectedError(f"{self} is not connected.") + + start = time.perf_counter() + + action = self.bus.sync_read(normalize=False, data_name="Present_Position") + action = {f"{motor}.pos": (val/4096*2*np.pi-np.pi) if motor != "gripper" else val for motor, val in action.items()} + + # # Normalize gripper position between 1 (closed) and 0 (open) + gripper_range = self.config.gripper_open_pos - self.config.gripper_closed_pos + action["gripper.pos"] = 1 - (action["gripper.pos"] - self.config.gripper_closed_pos) / gripper_range + + dt_ms = (time.perf_counter() - start) * 1e3 + logger.debug(f"{self} read action: {dt_ms:.1f}ms") + return action + + def send_feedback(self, feedback: dict[str, float]) -> None: + # TODO(rcadene, aliberts): Implement force feedback + raise NotImplementedError + + def disconnect(self) -> None: + if not self.is_connected: + raise DeviceNotConnectedError(f"{self} is not connected.") + + self.bus.disconnect() + logger.info(f"{self} disconnected.") \ No newline at end of file diff --git a/src/trlc_dk1/motors/DM_Control_Python/DM_CAN.py b/src/trlc_dk1/motors/DM_Control_Python/DM_CAN.py new file mode 100644 index 0000000000000000000000000000000000000000..d548f7fa04b1c6307b79e9b809bc8b518089ce55 --- /dev/null +++ b/src/trlc_dk1/motors/DM_Control_Python/DM_CAN.py @@ -0,0 +1,624 @@ +from time import sleep +import numpy as np +from enum import IntEnum +from struct import unpack +from struct import pack + + +class Motor: + def __init__(self, MotorType, SlaveID, MasterID): + """ + define Motor object 定义电机对象 + :param MotorType: Motor type 电机类型 + :param SlaveID: CANID 电机ID + :param MasterID: MasterID 主机ID 建议不要设为0 + """ + self.Pd = float(0) + self.Vd = float(0) + self.state_q = float(0) + self.state_dq = float(0) + self.state_tau = float(0) + self.SlaveID = SlaveID + self.MasterID = MasterID + self.MotorType = MotorType + self.isEnable = False + self.NowControlMode = Control_Type.MIT + self.temp_param_dict = {} + + def recv_data(self, q: float, dq: float, tau: float): + self.state_q = q + self.state_dq = dq + self.state_tau = tau + + def getPosition(self): + """ + get the position of the motor 获取电机位置 + :return: the position of the motor 电机位置 + """ + return self.state_q + + def getVelocity(self): + """ + get the velocity of the motor 获取电机速度 + :return: the velocity of the motor 电机速度 + """ + return self.state_dq + + def getTorque(self): + """ + get the torque of the motor 获取电机力矩 + :return: the torque of the motor 电机力矩 + """ + return self.state_tau + + def getParam(self, RID): + """ + get the parameter of the motor 获取电机内部的参数,需要提前读取 + :param RID: DM_variable 电机参数 + :return: the parameter of the motor 电机参数 + """ + if RID in self.temp_param_dict: + return self.temp_param_dict[RID] + else: + return None + + +class MotorControl: + send_data_frame = np.array( + [0x55, 0xAA, 0x1e, 0x03, 0x01, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0, 0, 0, 0, 0x00, 0x08, 0x00, + 0x00, 0, 0, 0, 0, 0, 0, 0, 0, 0x00], np.uint8) + # 4310 4310_48 4340 4340_48 + Limit_Param = [[12.5, 30, 10], [12.5, 50, 10], [12.5, 8, 28], [12.5, 10, 28], + # 6006 8006 8009 10010L 10010 + [12.5, 45, 20], [12.5, 45, 40], [12.5, 45, 54], [12.5, 25, 200], [12.5, 20, 200], + # H3510 DMG62150 DMH6220 + [12.5 , 280 , 1],[12.5 , 45 , 10],[12.5 , 45 , 10]] + + def __init__(self, serial_device): + """ + define MotorControl object 定义电机控制对象 + :param serial_device: serial object 串口对象 + """ + self.serial_ = serial_device + self.motors_map = dict() + self.data_save = bytes() # save data + if self.serial_.is_open: # open the serial port + print("Serial port is open") + serial_device.close() + self.serial_.open() + + def controlMIT(self, DM_Motor, kp: float, kd: float, q: float, dq: float, tau: float): + """ + MIT Control Mode Function 达妙电机MIT控制模式函数 + :param DM_Motor: Motor object 电机对象 + :param kp: kp + :param kd: kd + :param q: position 期望位置 + :param dq: velocity 期望速度 + :param tau: torque 期望力矩 + :return: None + """ + if DM_Motor.SlaveID not in self.motors_map: + print("controlMIT ERROR : Motor ID not found") + return + kp_uint = float_to_uint(kp, 0, 500, 12) + kd_uint = float_to_uint(kd, 0, 5, 12) + MotorType = DM_Motor.MotorType + Q_MAX = self.Limit_Param[MotorType][0] + DQ_MAX = self.Limit_Param[MotorType][1] + TAU_MAX = self.Limit_Param[MotorType][2] + q_uint = float_to_uint(q, -Q_MAX, Q_MAX, 16) + dq_uint = float_to_uint(dq, -DQ_MAX, DQ_MAX, 12) + tau_uint = float_to_uint(tau, -TAU_MAX, TAU_MAX, 12) + data_buf = np.array([0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00], np.uint8) + data_buf[0] = (q_uint >> 8) & 0xff + data_buf[1] = q_uint & 0xff + data_buf[2] = dq_uint >> 4 + data_buf[3] = ((dq_uint & 0xf) << 4) | ((kp_uint >> 8) & 0xf) + data_buf[4] = kp_uint & 0xff + data_buf[5] = kd_uint >> 4 + data_buf[6] = ((kd_uint & 0xf) << 4) | ((tau_uint >> 8) & 0xf) + data_buf[7] = tau_uint & 0xff + self.__send_data(DM_Motor.SlaveID, data_buf) + self.recv() # receive the data from serial port + + def control_delay(self, DM_Motor, kp: float, kd: float, q: float, dq: float, tau: float, delay: float): + """ + MIT Control Mode Function with delay 达妙电机MIT控制模式函数带延迟 + :param DM_Motor: Motor object 电机对象 + :param kp: kp + :param kd: kd + :param q: position 期望位置 + :param dq: velocity 期望速度 + :param tau: torque 期望力矩 + :param delay: delay time 延迟时间 单位秒 + """ + self.controlMIT(DM_Motor, kp, kd, q, dq, tau) + sleep(delay) + + def control_Pos_Vel(self, Motor, P_desired: float, V_desired: float): + """ + control the motor in position and velocity control mode 电机位置速度控制模式 + :param Motor: Motor object 电机对象 + :param P_desired: desired position 期望位置 + :param V_desired: desired velocity 期望速度 + :return: None + """ + if Motor.SlaveID not in self.motors_map: + print("Control Pos_Vel Error : Motor ID not found") + return + motorid = 0x100 + Motor.SlaveID + data_buf = np.array([0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00], np.uint8) + P_desired_uint8s = float_to_uint8s(P_desired) + V_desired_uint8s = float_to_uint8s(V_desired) + data_buf[0:4] = P_desired_uint8s + data_buf[4:8] = V_desired_uint8s + self.__send_data(motorid, data_buf) + # time.sleep(0.001) + self.recv() # receive the data from serial port + + def control_Vel(self, Motor, Vel_desired): + """ + control the motor in velocity control mode 电机速度控制模式 + :param Motor: Motor object 电机对象 + :param Vel_desired: desired velocity 期望速度 + """ + if Motor.SlaveID not in self.motors_map: + print("control_VEL ERROR : Motor ID not found") + return + motorid = 0x200 + Motor.SlaveID + data_buf = np.array([0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00], np.uint8) + Vel_desired_uint8s = float_to_uint8s(Vel_desired) + data_buf[0:4] = Vel_desired_uint8s + self.__send_data(motorid, data_buf) + self.recv() # receive the data from serial port + + def control_pos_force(self, Motor, Pos_des: float, Vel_des, i_des): + """ + control the motor in EMIT control mode 电机力位混合模式 + :param Pos_des: desired position rad 期望位置 单位为rad + :param Vel_des: desired velocity rad/s 期望速度 为放大100倍 + :param i_des: desired current rang 0-10000 期望电流标幺值放大10000倍 + 电流标幺值:实际电流值除以最大电流值,最大电流见上电打印 + """ + if Motor.SlaveID not in self.motors_map: + print("control_pos_vel ERROR : Motor ID not found") + return + motorid = 0x300 + Motor.SlaveID + data_buf = np.array([0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00], np.uint8) + Pos_desired_uint8s = float_to_uint8s(Pos_des) + data_buf[0:4] = Pos_desired_uint8s + Vel_uint = np.uint16(Vel_des) + ides_uint = np.uint16(i_des) + data_buf[4] = Vel_uint & 0xff + data_buf[5] = Vel_uint >> 8 + data_buf[6] = ides_uint & 0xff + data_buf[7] = ides_uint >> 8 + self.__send_data(motorid, data_buf) + self.recv() # receive the data from serial port + + def enable(self, Motor): + """ + enable motor 使能电机 + 最好在上电后几秒后再使能电机 + :param Motor: Motor object 电机对象 + """ + self.__control_cmd(Motor, np.uint8(0xFC)) + sleep(0.1) + self.recv() # receive the data from serial port + + def enable_old(self, Motor ,ControlMode): + """ + enable motor old firmware 使能电机旧版本固件,这个是为了旧版本电机固件的兼容性 + 可恶的旧版本固件使能需要加上偏移量 + 最好在上电后几秒后再使能电机 + :param Motor: Motor object 电机对象 + """ + data_buf = np.array([0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc], np.uint8) + enable_id = ((int(ControlMode)-1) << 2) + Motor.SlaveID + self.__send_data(enable_id, data_buf) + sleep(0.1) + self.recv() # receive the data from serial port + + def disable(self, Motor): + """ + disable motor 失能电机 + :param Motor: Motor object 电机对象 + """ + self.__control_cmd(Motor, np.uint8(0xFD)) + sleep(0.1) + self.recv() # receive the data from serial port + + def set_zero_position(self, Motor): + """ + set the zero position of the motor 设置电机0位 + :param Motor: Motor object 电机对象 + """ + self.__control_cmd(Motor, np.uint8(0xFE)) + sleep(0.1) + self.recv() # receive the data from serial port + + def recv(self): + # 把上次没有解析完的剩下的也放进来 + data_recv = b''.join([self.data_save, self.serial_.read_all()]) + packets = self.__extract_packets(data_recv) + for packet in packets: + data = packet[7:15] + CANID = (packet[6] << 24) | (packet[5] << 16) | (packet[4] << 8) | packet[3] + CMD = packet[1] + self.__process_packet(data, CANID, CMD) + + def recv_set_param_data(self): + data_recv = self.serial_.read_all() + packets = self.__extract_packets(data_recv) + for packet in packets: + data = packet[7:15] + CANID = (packet[6] << 24) | (packet[5] << 16) | (packet[4] << 8) | packet[3] + CMD = packet[1] + self.__process_set_param_packet(data, CANID, CMD) + + def __process_packet(self, data, CANID, CMD): + if CMD == 0x11: + if CANID != 0x00: + if CANID in self.motors_map: + q_uint = np.uint16((np.uint16(data[1]) << 8) | data[2]) + dq_uint = np.uint16((np.uint16(data[3]) << 4) | (data[4] >> 4)) + tau_uint = np.uint16(((data[4] & 0xf) << 8) | data[5]) + MotorType_recv = self.motors_map[CANID].MotorType + Q_MAX = self.Limit_Param[MotorType_recv][0] + DQ_MAX = self.Limit_Param[MotorType_recv][1] + TAU_MAX = self.Limit_Param[MotorType_recv][2] + recv_q = uint_to_float(q_uint, -Q_MAX, Q_MAX, 16) + recv_dq = uint_to_float(dq_uint, -DQ_MAX, DQ_MAX, 12) + recv_tau = uint_to_float(tau_uint, -TAU_MAX, TAU_MAX, 12) + self.motors_map[CANID].recv_data(recv_q, recv_dq, recv_tau) + else: + MasterID=data[0] & 0x0f + if MasterID in self.motors_map: + q_uint = np.uint16((np.uint16(data[1]) << 8) | data[2]) + dq_uint = np.uint16((np.uint16(data[3]) << 4) | (data[4] >> 4)) + tau_uint = np.uint16(((data[4] & 0xf) << 8) | data[5]) + MotorType_recv = self.motors_map[MasterID].MotorType + Q_MAX = self.Limit_Param[MotorType_recv][0] + DQ_MAX = self.Limit_Param[MotorType_recv][1] + TAU_MAX = self.Limit_Param[MotorType_recv][2] + recv_q = uint_to_float(q_uint, -Q_MAX, Q_MAX, 16) + recv_dq = uint_to_float(dq_uint, -DQ_MAX, DQ_MAX, 12) + recv_tau = uint_to_float(tau_uint, -TAU_MAX, TAU_MAX, 12) + self.motors_map[MasterID].recv_data(recv_q, recv_dq, recv_tau) + + + def __process_set_param_packet(self, data, CANID, CMD): + if CMD == 0x11 and (data[2] == 0x33 or data[2] == 0x55): + masterid=CANID + slaveId = ((data[1] << 8) | data[0]) + if CANID==0x00: #防止有人把MasterID设为0稳一手 + masterid=slaveId + + if masterid not in self.motors_map: + if slaveId not in self.motors_map: + return + else: + masterid=slaveId + + RID = data[3] + # 读取参数得到的数据 + if is_in_ranges(RID): + #uint32类型 + num = uint8s_to_uint32(data[4], data[5], data[6], data[7]) + self.motors_map[masterid].temp_param_dict[RID] = num + + else: + #float类型 + num = uint8s_to_float(data[4], data[5], data[6], data[7]) + self.motors_map[masterid].temp_param_dict[RID] = num + + + def addMotor(self, Motor): + """ + add motor to the motor control object 添加电机到电机控制对象 + :param Motor: Motor object 电机对象 + """ + self.motors_map[Motor.SlaveID] = Motor + if Motor.MasterID != 0: + self.motors_map[Motor.MasterID] = Motor + return True + + def __control_cmd(self, Motor, cmd: np.uint8): + data_buf = np.array([0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, cmd], np.uint8) + self.__send_data(Motor.SlaveID, data_buf) + + def __send_data(self, motor_id, data): + """ + send data to the motor 发送数据到电机 + :param motor_id: + :param data: + :return: + """ + self.send_data_frame[13] = motor_id & 0xff + self.send_data_frame[14] = (motor_id >> 8)& 0xff #id high 8 bits + self.send_data_frame[21:29] = data + self.serial_.write(bytes(self.send_data_frame.T)) + + def __read_RID_param(self, Motor, RID): + can_id_l = Motor.SlaveID & 0xff #id low 8 bits + can_id_h = (Motor.SlaveID >> 8)& 0xff #id high 8 bits + data_buf = np.array([np.uint8(can_id_l), np.uint8(can_id_h), 0x33, np.uint8(RID), 0x00, 0x00, 0x00, 0x00], np.uint8) + self.__send_data(0x7FF, data_buf) + + def __write_motor_param(self, Motor, RID, data): + can_id_l = Motor.SlaveID & 0xff #id low 8 bits + can_id_h = (Motor.SlaveID >> 8)& 0xff #id high 8 bits + data_buf = np.array([np.uint8(can_id_l), np.uint8(can_id_h), 0x55, np.uint8(RID), 0x00, 0x00, 0x00, 0x00], np.uint8) + if not is_in_ranges(RID): + # data is float + data_buf[4:8] = float_to_uint8s(data) + else: + # data is int + data_buf[4:8] = data_to_uint8s(int(data)) + self.__send_data(0x7FF, data_buf) + + def switchControlMode(self, Motor, ControlMode): + """ + switch the control mode of the motor 切换电机控制模式 + :param Motor: Motor object 电机对象 + :param ControlMode: Control_Type 电机控制模式 example:MIT:Control_Type.MIT MIT模式 + """ + max_retries = 20 + retry_interval = 0.1 #retry times + RID = 10 + self.__write_motor_param(Motor, RID, np.uint8(ControlMode)) + for _ in range(max_retries): + sleep(retry_interval) + self.recv_set_param_data() + if Motor.SlaveID in self.motors_map: + if RID in self.motors_map[Motor.SlaveID].temp_param_dict: + if abs(self.motors_map[Motor.SlaveID].temp_param_dict[RID] - ControlMode) < 0.1: + return True + else: + return False + return False + + def save_motor_param(self, Motor): + """ + save the all parameter to flash 保存所有电机参数 + :param Motor: Motor object 电机对象 + :return: + """ + can_id_l = Motor.SlaveID & 0xff #id low 8 bits + can_id_h = (Motor.SlaveID >> 8)& 0xff #id high 8 bits + data_buf = np.array([np.uint8(can_id_l), np.uint8(can_id_h), 0xAA, 0x00, 0x00, 0x00, 0x00, 0x00], np.uint8) + self.disable(Motor) # before save disable the motor + self.__send_data(0x7FF, data_buf) + sleep(0.001) + + def change_limit_param(self, Motor_Type, PMAX, VMAX, TMAX): + """ + change the PMAX VMAX TMAX of the motor 改变电机的PMAX VMAX TMAX + :param Motor_Type: + :param PMAX: 电机的PMAX + :param VMAX: 电机的VMAX + :param TMAX: 电机的TMAX + :return: + """ + self.Limit_Param[Motor_Type][0] = PMAX + self.Limit_Param[Motor_Type][1] = VMAX + self.Limit_Param[Motor_Type][2] = TMAX + + def refresh_motor_status(self,Motor): + """ + get the motor status 获得电机状态 + """ + can_id_l = Motor.SlaveID & 0xff #id low 8 bits + can_id_h = (Motor.SlaveID >> 8) & 0xff #id high 8 bits + data_buf = np.array([np.uint8(can_id_l), np.uint8(can_id_h), 0xCC, 0x00, 0x00, 0x00, 0x00, 0x00], np.uint8) + self.__send_data(0x7FF, data_buf) + self.recv() # receive the data from serial port + + def change_motor_param(self, Motor, RID, data): + """ + change the RID of the motor 改变电机的参数 + :param Motor: Motor object 电机对象 + :param RID: DM_variable 电机参数 + :param data: 电机参数的值 + :return: True or False ,True means success, False means fail + """ + max_retries = 20 + retry_interval = 0.05 #retry times + + self.__write_motor_param(Motor, RID, data) + for _ in range(max_retries): + self.recv_set_param_data() + if Motor.SlaveID in self.motors_map and RID in self.motors_map[Motor.SlaveID].temp_param_dict: + if abs(self.motors_map[Motor.SlaveID].temp_param_dict[RID] - data) < 0.1: + return True + else: + return False + sleep(retry_interval) + return False + + def read_motor_param(self, Motor, RID): + """ + read only the RID of the motor 读取电机的内部信息例如 版本号等 + :param Motor: Motor object 电机对象 + :param RID: DM_variable 电机参数 + :return: 电机参数的值 + """ + max_retries = 20 + retry_interval = 0.05 #retry times + self.__read_RID_param(Motor, RID) + for _ in range(max_retries): + sleep(retry_interval) + self.recv_set_param_data() + if Motor.SlaveID in self.motors_map: + if RID in self.motors_map[Motor.SlaveID].temp_param_dict: + return self.motors_map[Motor.SlaveID].temp_param_dict[RID] + return None + + # ------------------------------------------------- + # Extract packets from the serial data + def __extract_packets(self, data): + frames = [] + header = 0xAA + tail = 0x55 + frame_length = 16 + i = 0 + remainder_pos = 0 + + while i <= len(data) - frame_length: + if data[i] == header and data[i + frame_length - 1] == tail: + frame = data[i:i + frame_length] + frames.append(frame) + i += frame_length + remainder_pos = i + else: + i += 1 + self.data_save = data[remainder_pos:] + return frames + + +def LIMIT_MIN_MAX(x, min, max): + if x <= min: + x = min + elif x > max: + x = max + + +def float_to_uint(x: float, x_min: float, x_max: float, bits): + LIMIT_MIN_MAX(x, x_min, x_max) + span = x_max - x_min + data_norm = (x - x_min) / span + return np.uint16(data_norm * ((1 << bits) - 1)) + + +def uint_to_float(x: np.uint16, min: float, max: float, bits): + span = max - min + data_norm = float(x) / ((1 << bits) - 1) + temp = data_norm * span + min + return np.float32(temp) + + +def float_to_uint8s(value): + # Pack the float into 4 bytes + packed = pack('f', value) + # Unpack the bytes into four uint8 values + return unpack('4B', packed) + + +def data_to_uint8s(value): + # Check if the value is within the range of uint32 + if isinstance(value, int) and (0 <= value <= 0xFFFFFFFF): + # Pack the uint32 into 4 bytes + packed = pack('I', value) + else: + raise ValueError("Value must be an integer within the range of uint32") + + # Unpack the bytes into four uint8 values + return unpack('4B', packed) + + +def is_in_ranges(number): + """ + check if the number is in the range of uint32 + :param number: + :return: + """ + if (7 <= number <= 10) or (13 <= number <= 16) or (35 <= number <= 36): + return True + return False + + +def uint8s_to_uint32(byte1, byte2, byte3, byte4): + # Pack the four uint8 values into a single uint32 value in little-endian order + packed = pack('<4B', byte1, byte2, byte3, byte4) + # Unpack the packed bytes into a uint32 value + return unpack('=2.0.1 +pyserial>=3.5 \ No newline at end of file diff --git a/src/trlc_dk1/motors/__init__.py b/src/trlc_dk1/motors/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391