Skip to content
Commits on Source (31)
cmake_minimum_required(VERSION 3.8)
project(waterstridergazebo)
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(uuv_gazebo_ros_plugins_msgs REQUIRED)
find_package(Eigen3 REQUIRED COMPONENTS system)
include_directories(
# include
${EIGEN3_INCLUDE_DIRS}
)
install(DIRECTORY launch meshes robots urdf
DESTINATION share/${PROJECT_NAME}
PATTERN "*~"
EXCLUDE)
add_executable(thrusters_controller_node src/thrusters_controller_node.cpp)
ament_target_dependencies(thrusters_controller_node
rclcpp
std_msgs
geometry_msgs
uuv_gazebo_ros_plugins_msgs)
install(TARGETS thrusters_controller_node
DESTINATION lib/${PROJECT_NAME})
install(DIRECTORY config
DESTINATION share/${PROJECT_NAME}
PATTERN "*~"
EXCLUDE)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
set(DESCRIPTIONS_PYTHON_TESTS
test/test_urdf_files.py
)
foreach(T ${DESCRIPTIONS_PYTHON_TESTS})
get_filename_component(_test_name ${T} NAME_WE)
ament_add_pytest_test(${_test_name} ${T}
PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE}"
APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}
PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR}
TIMEOUT 120
)
endforeach()
endif()
ament_export_dependencies(EIGEN3)
ament_package()
# VaterstriderGazebo
## Getting started
To make it easy for you to get started with GitLab, here's a list of recommended next steps.
Already a pro? Just edit this README.md and make it your own. Want to make it easy? [Use the template at the bottom](#editing-this-readme)!
## Add your files
- [ ] [Create](https://docs.gitlab.com/ee/user/project/repository/web_editor.html#create-a-file) or [upload](https://docs.gitlab.com/ee/user/project/repository/web_editor.html#upload-a-file) files
- [ ] [Add files using the command line](https://docs.gitlab.com/ee/gitlab-basics/add-file.html#add-a-file-using-the-command-line) or push an existing Git repository with the following command:
# Waterstrider simulation
## Launch robot
Setup source:
```bash
source /opt/ros/iron/setup.bash
source $HOME/ros2_ws/install/setup.bash
source /usr/share/gazebo/setup.sh
```
cd existing_repo
git remote add origin https://gitlab.dnouglublenie.ru/skb/vaterstridergazebo.git
git branch -M master
git push -uf origin master
Launch an ocean world (Plankton package):
```bash
ros2 launch uuv_gazebo_worlds lake.launch
```
## Integrate with your tools
- [ ] [Set up project integrations](https://gitlab.dnouglublenie.ru/skb/vaterstridergazebo/-/settings/integrations)
## Collaborate with your team
- [ ] [Invite team members and collaborators](https://docs.gitlab.com/ee/user/project/members/)
- [ ] [Create a new merge request](https://docs.gitlab.com/ee/user/project/merge_requests/creating_merge_requests.html)
- [ ] [Automatically close issues from merge requests](https://docs.gitlab.com/ee/user/project/issues/managing_issues.html#closing-issues-automatically)
- [ ] [Enable merge request approvals](https://docs.gitlab.com/ee/user/project/merge_requests/approvals/)
- [ ] [Set auto-merge](https://docs.gitlab.com/ee/user/project/merge_requests/merge_when_pipeline_succeeds.html)
## Test and Deploy
Use the built-in continuous integration in GitLab.
- [ ] [Get started with GitLab CI/CD](https://docs.gitlab.com/ee/ci/quick_start/index.html)
- [ ] [Analyze your code for known vulnerabilities with Static Application Security Testing (SAST)](https://docs.gitlab.com/ee/user/application_security/sast/)
- [ ] [Deploy to Kubernetes, Amazon EC2, or Amazon ECS using Auto Deploy](https://docs.gitlab.com/ee/topics/autodevops/requirements.html)
- [ ] [Use pull-based deployments for improved Kubernetes management](https://docs.gitlab.com/ee/user/clusters/agent/)
- [ ] [Set up protected environments](https://docs.gitlab.com/ee/ci/environments/protected_environments.html)
***
# Editing this README
When you're ready to make this README your own, just edit this file and use the handy template below (or feel free to structure it however you want - this is just a starting point!). Thanks to [makeareadme.com](https://www.makeareadme.com/) for this template.
## Suggestions for a good README
Every project is different, so consider which of these sections apply to yours. The sections used in the template are suggestions for most open source projects. Also keep in mind that while a README can be too long and detailed, too long is better than too short. If you think your README is too long, consider utilizing another form of documentation rather than cutting out information.
## Name
Choose a self-explaining name for your project.
## Description
Let people know what your project can do specifically. Provide context and add a link to any reference visitors might be unfamiliar with. A list of Features or a Background subsection can also be added here. If there are alternatives to your project, this is a good place to list differentiating factors.
## Badges
On some READMEs, you may see small images that convey metadata, such as whether or not all the tests are passing for the project. You can use Shields to add some to your README. Many services also have instructions for adding a badge.
## Visuals
Depending on what you are making, it can be a good idea to include screenshots or even a video (you'll frequently see GIFs rather than actual videos). Tools like ttygif can help, but check out Asciinema for a more sophisticated method.
## Installation
Within a particular ecosystem, there may be a common way of installing things, such as using Yarn, NuGet, or Homebrew. However, consider the possibility that whoever is reading your README is a novice and would like more guidance. Listing specific steps helps remove ambiguity and gets people to using your project as quickly as possible. If it only runs in a specific context like a particular programming language version or operating system or has dependencies that have to be installed manually, also add a Requirements subsection.
## Usage
Use examples liberally, and show the expected output if you can. It's helpful to have inline the smallest example of usage that you can demonstrate, while providing links to more sophisticated examples if they are too long to reasonably include in the README.
## Support
Tell people where they can go to for help. It can be any combination of an issue tracker, a chat room, an email address, etc.
## Roadmap
If you have ideas for releases in the future, it is a good idea to list them in the README.
## Contributing
State if you are open to contributions and what your requirements are for accepting them.
For people who want to make changes to your project, it's helpful to have some documentation on how to get started. Perhaps there is a script that they should run or some environment variables that they need to set. Make these steps explicit. These instructions could also be useful to your future self.
You can also document commands to lint the code or run tests. These steps help to ensure high code quality and reduce the likelihood that the changes inadvertently break something. Having instructions for running tests is especially helpful if it requires external setup, such as starting a Selenium server for testing in a browser.
## Authors and acknowledgment
Show your appreciation to those who have contributed to the project.
## License
For open source projects, say how it is licensed.
## Project status
If you have run out of energy or time for your project, put a note at the top of the README saying that development has slowed down or stopped completely. Someone may choose to fork your project or volunteer to step in as a maintainer or owner, allowing your project to keep going. You can also make an explicit request for maintainers.
Launch a robot in the world
```bash
ros2 launch waterstridergazebo upload_waterstrider_launch.py
```
## Teleoperation
Launch thrusters controller for any type of teleoperation
```bash
ros2 launch waterstridergazebo thrusters_controller_launch.py
```
Keyboard teleoperation
```bash
ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap cmd_vel:=waterstrider/twist_command
```
Joystick teleoperation
```bash
ros2 launch waterstridergazebo joy_teleop.launch
```
\ No newline at end of file
/**:
ros__parameters:
qos_overrides:
/parameter_events:
publisher:
depth: 1000
durability: volatile
history: keep_last
reliability: reliable
start_type_description_service: true
use_sim_time: false
thrusters:
controller_output_0:
enabled: true
f: [ -0.99, 0.01, 0.00]
r: [ -2.2795, -1.50, -0.8897]
input: [-1.0, 0.0, 1.0]
output: [-700.0, 0.0, 700.0]
controller_output_1:
enabled: true
f: [ -0.99, -0.01, 0.00]
r: [ -2.2795, 1.50, -0.8897]
input: [-1.0, 0.0, 1.0]
output: [-700.0, 0.0, 700.0]
import os
from ament_index_python import get_package_share_directory
from launch import LaunchDescription
from launch.actions import GroupAction, IncludeLaunchDescription
from launch_ros.actions import Node, PushRosNamespace
from launch_xml.launch_description_sources import XMLLaunchDescriptionSource
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
ld = LaunchDescription()
gazebo = IncludeLaunchDescription(XMLLaunchDescriptionSource(os.path.join(get_package_share_directory('uuv_gazebo_worlds'), 'launch/ocean_waves.launch')))
ld.add_action(gazebo)
waterstider = IncludeLaunchDescription(PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('waterstridergazebo'), 'launch/upload_waterstrider_launch.py')))
ld.add_action(waterstider)
thruster_controller = IncludeLaunchDescription(PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('waterstridergazebo'), 'launch/thrusters_controller_launch.py')))
ld.add_action(thruster_controller)
return ld
\ No newline at end of file
<?xml version="1.0"?>
<launch>
<include file="$(find-pkg-share uuv_teleop)/launch/uuv_teleop.launch">
<arg name="uuv_name" value="waterstrider"/>
<arg name="joy_id" value="0"/>
<arg name="output_topic" value="twist_command"/>
<arg name="message_type" value="twist"/>
<arg name="gain_roll" value="0.0"/>
<arg name="gain_pitch" value="1.0"/>
<arg name="gain_yaw" value="0.6"/>
<arg name="gain_x" value="1.0"/>
<arg name="gain_y" value="1.0"/>
<arg name="gain_z" value="1.0"/>
</include>
</launch>
ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap cmd_vel:=waterstrider/twist_command
import os
from ament_index_python import get_package_share_directory
from launch import LaunchDescription
from launch.actions import GroupAction
from launch_ros.actions import Node, PushRosNamespace
from launch.substitutions import LaunchConfiguration as Lc
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
def to_bool(value: str):
if isinstance(value, bool):
return value
if not isinstance(value, str):
raise ValueError('String to bool, invalid type ' + str(value))
valid = {'true': True, '1': True,
'false': False, '0': False}
if value.lower() in valid:
return valid[value]
raise ValueError('String to bool, invalid value: %s' % value)
def launch_setup(context, *args, **kwargs):
namespace = Lc('namespace').perform(context)
is_use_namespace = to_bool(Lc("is_use_namespace").perform(context))
if is_use_namespace:
return [GroupAction([
PushRosNamespace(namespace),
Node(
package='waterstridergazebo',
executable='thrusters_controller_node',
output='screen',
parameters=[os.path.join(
get_package_share_directory('waterstridergazebo'),
'config',
'waterstrider_thrusters.yaml'
)],
remappings=[
('thrusters/controller_output_0', 'thrusters/id_0/input'),
('thrusters/controller_output_1', 'thrusters/id_1/input'),
]
)
])]
return [GroupAction([
Node(
package='waterstridergazebo',
executable='thrusters_controller_node',
output='screen',
parameters=[os.path.join(
get_package_share_directory('waterstridergazebo'),
'config',
'waterstrider_thrusters.yaml'
)],
remappings=[
('thrusters/controller_output_0', 'thrusters/id_0/input'),
('thrusters/controller_output_1', 'thrusters/id_1/input'),
]
)
])]
def generate_launch_description():
return LaunchDescription([
DeclareLaunchArgument('namespace', default_value='waterstrider'),
DeclareLaunchArgument('is_use_namespace', default_value='true'),
OpaqueFunction(function=launch_setup)
])
# Copyright (c) 2020 The Plankton Authors.
# All rights reserved.
#
# This source code is derived from UUV Simulator
# (https://github.com/uuvsimulator/uuv_simulator)
# Copyright (c) 2016-2019 The UUV Simulator Authors
# licensed under the Apache license, Version 2.0
# cf. 3rd-party-licenses.txt file in the root directory of this source tree.
#
from launch import LaunchDescription
from launch.launch_description_sources import AnyLaunchDescriptionSource
from launch_ros.actions import Node, PushRosNamespace
from launch.actions import DeclareLaunchArgument
from launch.actions import GroupAction
from launch.actions import OpaqueFunction
from launch.actions import IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration as Lc
import launch_testing.actions
from ament_index_python.packages import get_package_share_directory
import os
import pathlib
import xacro
from plankton_utils.time import is_sim_time
def to_bool(value: str):
if isinstance(value, bool):
return value
if not isinstance(value, str):
raise ValueError('String to bool, invalid type ' + str(value))
valid = {'true': True, '1': True,
'false': False, '0': False}
if value.lower() in valid:
return valid[value]
raise ValueError('String to bool, invalid value: %s' % value)
# =============================================================================
def launch_setup(context, *args, **kwargs):
# Perform substitutions
debug = Lc('debug').perform(context)
namespace = Lc('namespace').perform(context)
x = Lc('x').perform(context)
y = Lc('y').perform(context)
z = Lc('z').perform(context)
roll = Lc('roll').perform(context)
pitch = Lc('pitch').perform(context)
yaw = Lc('yaw').perform(context)
# use_sim_time = Lc('use_sim_time').perform(context)
use_world_ned = Lc('use_ned_frame').perform(context)
is_write_on_disk = Lc('write_file_on_disk').perform(context)
# Request sim time value to the global node
res = is_sim_time(return_param=False, use_subprocess=True)
# Xacro
xacro_file = os.path.join(
get_package_share_directory('waterstridergazebo'),
'robots',
'waterstrider_' + (Lc('mode')).perform(context) + '.xacro'
)
# Build the directories, check for existence
path = os.path.join(
get_package_share_directory('uuv_descriptions'),
'robots',
'generated',
namespace,
)
if not pathlib.Path(path).exists():
try:
# Create directory if required and sub-directory
os.makedirs(path)
except OSError:
print("Creation of the directory %s failed" % path)
output = os.path.join(
path,
'robot_description.urdf'
)
if not pathlib.Path(xacro_file).exists():
exc = 'Launch file ' + xacro_file + ' does not exist'
raise Exception(exc)
if to_bool(use_world_ned):
mappings = {'debug': debug, 'namespace': namespace, 'inertial_reference_frame': 'world_ned'}
else:
mappings = {'debug': debug, 'namespace': namespace, 'inertial_reference_frame': 'world'}
doc = xacro.process(xacro_file, mappings=mappings)
if is_write_on_disk:
with open(output, 'w') as file_out:
file_out.write(doc)
# URDF spawner
args = ('-x %s -y %s -z %s -R %s -P %s -Y %s -entity %s -topic robot_description'
% (x, y, z, roll, pitch, yaw, namespace)).split()
# Urdf spawner. NB: node namespace does not prefix the spawning service,
# as using a leading /
# NB 2: node namespace prefixes the robot_description topic
urdf_spawner = Node(
name='urdf_spawner',
package='gazebo_ros',
executable='spawn_entity.py',
output='screen',
parameters=[{'use_sim_time': res}],
arguments=args,
)
# A joint state publisher plugin already is started with the model, no need to use the default joint state publisher
# N.B.: alternative way to generate a robot_description string:
# string = str('ros2 run xacro xacro ' + xacro_file + ' debug:=false namespace:=' + namespace + ' inertial_reference_frame:=world')
# cmd = Command(string)
# but it currently yields yaml parsing error due to ":" in the comments of the xacro description files
robot_state_publisher = Node(
name='robot_state_publisher',
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[{'use_sim_time': res}, {'robot_description': doc}], # Use subst here
)
# Thrusters remapings
thrusters_transformers = [Node(package='topic_tools',
executable='transform',
arguments=[f'/waterstrider/thrusters/controller_output_{i}',
f'/waterstrider/thrusters/id_{i}/input',
'uuv_gazebo_ros_plugins_msgs/FloatStamped',
'uuv_gazebo_ros_plugins_msgs.msg.FloatStamped(data=m.data)',
'--wait-for-start',
'--import',
'uuv_gazebo_ros_plugins_msgs'
]) for i in range(8)]
# Message to tf
message_to_tf_launch = os.path.join(
get_package_share_directory('uuv_assistants'),
'launch',
'message_to_tf.launch'
)
if not pathlib.Path(message_to_tf_launch).exists():
exc = 'Launch file ' + message_to_tf_launch + ' does not exist'
raise Exception(exc)
launch_args = [('namespace', namespace), ('world_frame', 'world'),
('child_frame_id', '/' + namespace + '/base_link'), ('use_sim_time', str(res).lower()), ]
message_to_tf_launch = IncludeLaunchDescription(
AnyLaunchDescriptionSource(message_to_tf_launch), launch_arguments=launch_args)
group = GroupAction([
PushRosNamespace(namespace),
urdf_spawner,
robot_state_publisher,
*thrusters_transformers
])
return [group, message_to_tf_launch]
# =============================================================================
def generate_launch_description():
# TODO Try LaunchContext ?
return LaunchDescription([
DeclareLaunchArgument('debug', default_value='0'),
DeclareLaunchArgument('x', default_value='0'),
DeclareLaunchArgument('y', default_value='0'),
DeclareLaunchArgument('z', default_value='0'),
DeclareLaunchArgument('roll', default_value='0.0'),
DeclareLaunchArgument('pitch', default_value='0.0'),
DeclareLaunchArgument('yaw', default_value='3.1415926'),
DeclareLaunchArgument('mode', default_value='default'),
DeclareLaunchArgument('namespace', default_value='waterstrider'),
DeclareLaunchArgument('use_ned_frame', default_value='false'),
DeclareLaunchArgument('write_file_on_disk', default_value='false'),
# DeclareLaunchArgument('use_sim_time', default_value='true'),
OpaqueFunction(function=launch_setup)
])
# Blender 4.3.2 MTL File: 'None'
# www.blender.org
newmtl mat_1
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_10
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_11
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_12
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_13
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_14
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_15
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_2
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_3
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_4
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_5
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_6
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_7
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_8
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_9
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
# Blender 4.3.2
# www.blender.org
mtllib new_prop.mtl
o waterstrider.001
v 11.503677 27.332748 4.741090
v 11.263626 27.527794 4.547410
v 10.989609 27.668961 4.341875
v 11.503677 27.332748 1.970002
v 10.989609 27.668961 1.480775
v 11.264038 27.527451 1.733705
v -11.609421 -11.935676 -12.289277
v -9.406158 -13.784415 -12.289277
v -6.915359 -15.222495 -12.289277
v -4.212662 -16.206184 -12.289277
v -1.380219 -16.705620 -12.289277
v 1.495911 -16.705620 -12.289277
v 4.328354 -16.206184 -12.289277
v 7.031052 -15.222495 -12.289277
v 9.521851 -13.784415 -12.289277
v 11.725113 -11.935676 -12.289277
v 13.573853 -9.732413 -12.289276
v 15.011917 -7.241615 -12.289276
v 15.995621 -4.538925 -12.289276
v 16.495056 -1.706481 -12.289276
v 16.495056 1.169663 -12.289276
v 15.995621 4.002106 -12.289276
v 15.011917 6.704789 -12.289276
v 13.573853 9.195603 -12.289276
v 11.725113 11.398850 -12.289275
v 11.725113 11.398849 5.606537
v 12.948349 10.031342 6.893784
v 14.012207 8.536476 8.079590
v 14.012207 8.536476 10.330948
v 11.725113 11.398849 8.360581
v 12.935913 10.046898 9.387329
v 11.725113 11.398849 17.710724
v 13.573853 9.195601 17.710724
v 15.011917 6.704787 17.710724
v 15.995621 4.002105 17.710724
v 16.495056 1.169662 17.710724
v 16.495056 -1.706483 17.710724
v 15.995621 -4.538926 17.710724
v 15.011917 -7.241616 17.710724
v 13.573853 -9.732415 17.710724
v 11.725113 -11.935678 17.710724
v 9.521851 -13.784417 17.710724
v 7.031052 -15.222497 17.710724
v 4.328354 -16.206184 17.710724
v 1.495911 -16.705620 17.710724
v -1.380219 -16.705620 17.710724
v -4.212662 -16.206184 17.710724
v -6.915359 -15.222497 17.710724
v -9.406158 -13.784417 17.710724
v -11.609421 -11.935678 17.710724
v 0.705917 -16.755684 10.330947
v 0.705917 -16.755684 8.079589
v 14.413895 -8.401917 -2.760666
v 12.331528 -11.295952 1.016113
v 10.022125 -13.419823 3.841842
v 7.404373 -15.043144 6.215637
v 4.692200 -16.104225 8.133483
v 2.744232 -16.548271 9.282348
v 14.413895 -8.401917 -4.998246
v 12.315567 -11.313683 -2.028351
v 9.541168 -13.770882 1.072860
v 6.606735 -15.413109 3.785827
v 3.766861 -16.346138 6.022354
v 2.230881 -16.624687 7.097976
v 1.393082 29.701859 -6.731184
v 5.737259 29.189087 -3.102202
v 8.402527 28.547668 -0.804793
v 10.989609 27.668961 1.480775
v 1.393082 29.701859 -4.035414
v 4.453552 29.407913 -1.005232
v 7.684891 28.745842 1.799028
v 10.989609 27.668961 4.341875
v -26.564789 -14.097206 -6.731186
v -28.292801 -10.078651 -3.102204
v -29.069946 -7.449745 -0.804795
v -29.602509 -4.769913 1.480774
v -26.564789 -14.097206 -4.035416
v -27.840454 -11.299782 -1.005234
v -28.882759 -8.170319 1.799026
v -29.602509 -4.769913 4.341873
v 11.852295 26.785851 2.370942
v 13.510712 20.850891 5.001588
v 14.209579 15.313980 6.768891
v 14.254456 11.910431 7.543702
v 14.012207 8.536476 8.079590
v 11.852295 26.785851 5.076768
v 13.484100 20.984314 7.309098
v 14.231628 14.876953 9.062531
v 14.248306 11.715881 9.764298
v 14.012207 8.536476 10.330948
v -14.164001 -8.634361 -2.760666
v -14.164001 -8.634361 -4.998246
v -24.473114 -14.698662 -7.672059
v -24.473114 -14.698662 -5.434464
v -0.076355 16.231041 -2.760665
v -0.076355 16.231041 -4.998245
v -0.173630 28.191147 -7.672057
v -0.173630 28.191147 -5.434462
v -29.269058 -3.581253 2.370941
v -24.958435 0.822456 5.001587
v -20.512772 4.196159 6.768890
v -17.587646 5.936790 7.543702
v -14.544586 7.413970 8.079590
v -29.269058 -3.581253 5.076767
v -25.051086 0.741157 7.313263
v -20.140625 4.436759 9.063889
v -17.419632 6.026771 9.763397
v -14.544586 7.413970 10.330948
v 25.345245 -16.409889 -4.035417
v 23.560455 -18.913368 -1.005235
v 21.371399 -21.380760 1.799026
v 18.786438 -23.704277 4.341872
v 18.786438 -23.704277 1.480773
v 25.345245 -16.409889 -6.731187
v 22.729080 -19.915672 -3.102204
v 20.840958 -21.903145 -0.804795
v 17.590302 -24.009834 2.370940
v 11.621262 -22.478584 5.001586
v 6.476715 -20.315376 6.768889
v 3.506729 -18.652443 7.543700
v 0.705917 -16.755684 8.079589
v 17.590302 -24.009834 5.076766
v 11.765060 -22.527290 7.303939
v 6.076279 -20.110207 9.065459
v 3.336945 -18.547142 9.765334
v 0.705917 -16.755684 10.330947
v 14.413895 -8.401917 -2.760666
v 14.413895 -8.401917 -4.998246
v 24.820282 -14.297722 -7.672059
v 24.820282 -14.297722 -5.434464
v 25.345245 -16.409889 -6.731187
v 22.729080 -19.915672 -3.102204
v 20.840958 -21.903145 -0.804795
v 18.786438 -23.704277 1.480773
v 18.519516 -23.874779 1.740065
v 18.221268 -23.985817 1.982695
v 17.906937 -24.031410 2.196044
v 17.590302 -24.009834 2.370940
v 11.621262 -22.478584 5.001586
v 6.476715 -20.315376 6.768889
v 3.506729 -18.652443 7.543700
v 0.705917 -16.755684 8.079589
v 14.413895 -8.401917 -4.998246
v 12.315567 -11.313683 -2.028351
v 9.541168 -13.770882 1.072860
v 6.606735 -15.413109 3.785827
v 3.766861 -16.346138 6.022354
v 2.230881 -16.624687 7.097976
v 24.820282 -14.297722 -7.672059
v 25.141541 -14.542152 -7.717591
v 25.400986 -14.890556 -7.664856
v 25.517975 -15.173012 -7.566773
v 25.580856 -15.609123 -7.345536
v 25.516418 -16.037804 -7.053223
v 11.725113 11.398850 -12.289275
v 11.725113 11.398849 5.606537
v 9.521851 13.247598 -12.289275
v 7.031052 14.685670 -12.289275
v 4.328354 15.669366 -12.289275
v 1.495911 16.168800 -12.289275
v -1.380219 16.168800 -12.289275
v -4.212662 15.669366 -12.289275
v -6.915359 14.685670 -12.289275
v -9.406158 13.247598 -12.289275
v -11.609421 11.398850 -12.289275
v -13.458160 9.195603 -12.289276
v -14.896225 6.704789 -12.289276
v -15.879929 4.002106 -12.289276
v -16.379364 1.169663 -12.289276
v -16.379364 -1.706481 -12.289276
v -15.879929 -4.538925 -12.289276
v -14.896225 -7.241615 -12.289276
v -13.458160 -9.732413 -12.289276
v -11.609421 -11.935676 -12.289277
v -11.609421 -11.935678 17.710724
v -13.458160 -9.732415 17.710724
v -14.896225 -7.241616 17.710724
v -15.879929 -4.538926 17.710724
v -16.379364 -1.706483 17.710724
v -16.379364 1.169662 17.710724
v -15.879929 4.002105 17.710724
v -14.896225 6.704787 17.710724
v -13.458160 9.195601 17.710724
v -11.609421 11.398849 17.710724
v -9.406158 13.247596 17.710724
v -6.915359 14.685668 17.710724
v -4.212662 15.669364 17.710724
v -1.380219 16.168800 17.710724
v 1.495911 16.168800 17.710724
v 4.328354 15.669364 17.710724
v 7.031052 14.685668 17.710724
v 9.521851 13.247596 17.710724
v 11.725113 11.398849 17.710724
v 11.725113 11.398849 8.360581
v -0.076355 16.231041 -2.760665
v 3.455994 15.877884 1.001084
v 6.437332 14.948395 3.816758
v 9.142349 13.505562 6.183777
v 10.465591 12.535385 7.302796
v -0.076355 16.231041 -4.998245
v 3.403976 15.888741 -2.105758
v 6.797852 14.792213 0.880387
v 9.440994 13.303864 3.343613
v -14.164001 -8.634361 -2.760666
v -15.629135 -5.383957 1.016113
v -16.313751 -2.322022 3.841843
v -16.410721 0.756683 6.215637
v -15.973541 3.636024 8.133484
v -15.384109 5.545043 9.282349
v -14.544586 7.413970 10.330948
v -14.164001 -8.634361 -4.998246
v -15.636505 -5.361275 -2.028351
v -16.377289 -1.729980 1.072861
v -16.332291 1.632431 3.785828
v -15.720383 4.558349 6.022354
v -15.193619 6.027832 7.097977
v -14.544586 7.413970 8.079590
v -11.609421 -11.935676 -12.289277
v -9.406158 -13.784415 -12.289277
v -6.915359 -15.222495 -12.289277
v -4.212662 -16.206184 -12.289277
v -1.380219 -16.705620 -12.289277
v 1.495911 -16.705620 -12.289277
v 4.328354 -16.206184 -12.289277
v 7.031052 -15.222495 -12.289277
v 9.521851 -13.784415 -12.289277
v 11.725113 -11.935676 -12.289277
v 13.573853 -9.732413 -12.289276
v 15.011917 -7.241615 -12.289276
v 15.995621 -4.538925 -12.289276
v 16.495056 -1.706481 -12.289276
v 16.495056 1.169663 -12.289276
v 15.995621 4.002106 -12.289276
v 15.011917 6.704789 -12.289276
v 13.573853 9.195603 -12.289276
v 11.725113 11.398850 -12.289275
v 9.521851 13.247598 -12.289275
v 7.031052 14.685670 -12.289275
v 4.328354 15.669366 -12.289275
v 1.495911 16.168800 -12.289275
v -1.380219 16.168800 -12.289275
v -4.212662 15.669366 -12.289275
v -6.915359 14.685670 -12.289275
v -9.406158 13.247598 -12.289275
v -11.609421 11.398850 -12.289275
v -13.458160 9.195603 -12.289276
v -14.896225 6.704789 -12.289276
v -15.879929 4.002106 -12.289276
v -16.379364 1.169663 -12.289276
v -16.379364 -1.706481 -12.289276
v -15.879929 -4.538925 -12.289276
v -14.896225 -7.241615 -12.289276
v -13.458160 -9.732413 -12.289276
v 7.659241 -5.394935 -12.289276
v 7.855316 -5.628616 -12.289276
v 8.007843 -5.892791 -12.289276
v 8.112183 -6.179435 -12.289276
v 8.165146 -6.479850 -12.289276
v 8.165146 -6.784896 -12.289276
v 8.112183 -7.085304 -12.289276
v 8.007843 -7.371955 -12.289276
v 7.855316 -7.636131 -12.289276
v 7.659241 -7.869804 -12.289276
v 7.425568 -8.065886 -12.289276
v 7.161392 -8.218406 -12.289276
v 6.874741 -8.322738 -12.289276
v 6.574326 -8.375709 -12.289276
v 6.269287 -8.375709 -12.289276
v 5.968872 -8.322738 -12.289276
v 5.682220 -8.218406 -12.289276
v 5.418045 -8.065886 -12.289276
v 5.184372 -7.869804 -12.289276
v 4.988297 -7.636131 -12.289276
v 4.835770 -7.371955 -12.289276
v 4.731430 -7.085304 -12.289276
v 4.678467 -6.784896 -12.289276
v 4.678467 -6.479850 -12.289276
v 4.731430 -6.179435 -12.289276
v 4.835770 -5.892791 -12.289276
v 4.988297 -5.628616 -12.289276
v 5.184372 -5.394935 -12.289276
v 5.418045 -5.198852 -12.289276
v 5.682220 -5.046333 -12.289276
v 5.968872 -4.942001 -12.289276
v 6.269287 -4.889030 -12.289276
v 6.574326 -4.889030 -12.289276
v 6.874741 -4.942001 -12.289276
v 7.161392 -5.046333 -12.289276
v 7.425568 -5.198852 -12.289276
v -5.068680 7.332985 -12.289276
v -4.872604 7.099312 -12.289276
v -4.720078 6.835137 -12.289276
v -4.615738 6.548485 -12.289276
v -4.562775 6.248070 -12.289276
v -4.562775 5.943032 -12.289276
v -4.615738 5.642617 -12.289276
v -4.720078 5.355973 -12.289276
v -4.872604 5.091790 -12.289276
v -5.068680 4.858117 -12.289276
v -5.302353 4.662034 -12.289276
v -5.566528 4.509514 -12.289276
v -5.853180 4.405182 -12.289276
v -6.153595 4.352211 -12.289276
v -6.458633 4.352211 -12.289276
v -6.759048 4.405182 -12.289276
v -7.045700 4.509514 -12.289276
v -7.309875 4.662034 -12.289276
v -7.543549 4.858117 -12.289276
v -7.739624 5.091790 -12.289276
v -7.892151 5.355973 -12.289276
v -7.996490 5.642617 -12.289276
v -8.049454 5.943032 -12.289276
v -8.049454 6.248070 -12.289276
v -7.996490 6.548485 -12.289276
v -7.892151 6.835137 -12.289276
v -7.739624 7.099312 -12.289276
v -7.543549 7.332985 -12.289276
v -7.309875 7.529068 -12.289276
v -7.045700 7.681588 -12.289276
v -6.759048 7.785920 -12.289276
v -6.458633 7.838891 -12.289276
v -6.153595 7.838891 -12.289276
v -5.853180 7.785920 -12.289276
v -5.566528 7.681588 -12.289276
v -5.302353 7.529068 -12.289276
v 3.946930 3.620675 -12.289276
v 4.563187 2.886261 -12.289276
v 5.042542 2.055993 -12.289276
v 5.370438 1.155099 -12.289276
v 5.536911 0.210946 -12.289276
v 5.536911 -0.747764 -12.289276
v 5.370438 -1.691917 -12.289276
v 5.042542 -2.592811 -12.289276
v 4.563187 -3.423080 -12.289276
v 3.946930 -4.157501 -12.289276
v 3.212509 -4.773750 -12.289276
v 2.382248 -5.253105 -12.289276
v 1.481354 -5.581001 -12.289276
v 0.537201 -5.747482 -12.289276
v -0.421509 -5.747482 -12.289276
v -1.365662 -5.581001 -12.289276
v -2.266556 -5.253105 -12.289276
v -3.096817 -4.773750 -12.289276
v -3.831238 -4.157501 -12.289276
v -4.447495 -3.423080 -12.289276
v -4.926849 -2.592811 -12.289276
v -5.254745 -1.691917 -12.289276
v -5.421219 -0.747764 -12.289276
v -5.421219 0.210946 -12.289276
v -5.254745 1.155099 -12.289276
v -4.926849 2.055993 -12.289276
v -4.447495 2.886261 -12.289276
v -3.831238 3.620675 -12.289276
v -3.096817 4.236924 -12.289276
v -2.266556 4.716286 -12.289276
v -1.365662 5.044182 -12.289276
v -0.421509 5.210663 -12.289276
v 0.537201 5.210663 -12.289276
v 1.481354 5.044182 -12.289276
v 2.382248 4.716286 -12.289276
v 3.212509 4.236924 -12.289276
v 11.725113 11.398849 17.710724
v 13.573853 9.195601 17.710724
v 15.011917 6.704787 17.710724
v 15.995621 4.002105 17.710724
v 16.495056 1.169662 17.710724
v 16.495056 -1.706483 17.710724
v 15.995621 -4.538926 17.710724
v 15.011917 -7.241616 17.710724
v 13.573853 -9.732415 17.710724
v 11.725113 -11.935678 17.710724
v 9.521851 -13.784417 17.710724
v 7.031052 -15.222497 17.710724
v 4.328354 -16.206184 17.710724
v 1.495911 -16.705620 17.710724
v -1.380219 -16.705620 17.710724
v -4.212662 -16.206184 17.710724
v -6.915359 -15.222497 17.710724
v -9.406158 -13.784417 17.710724
v -11.609421 -11.935678 17.710724
v -13.458160 -9.732415 17.710724
v -14.896225 -7.241616 17.710724
v -15.879929 -4.538926 17.710724
v -16.379364 -1.706483 17.710724
v -16.379364 1.169662 17.710724
v -15.879929 4.002105 17.710724
v -14.896225 6.704787 17.710724
v -13.458160 9.195601 17.710724
v -11.609421 11.398849 17.710724
v -9.406158 13.247596 17.710724
v -6.915359 14.685668 17.710724
v -4.212662 15.669364 17.710724
v -1.380219 16.168800 17.710724
v 1.495911 16.168800 17.710724
v 4.328354 15.669364 17.710724
v 7.031052 14.685668 17.710724
v 9.521851 13.247596 17.710724
v 10.310898 9.984633 17.710724
v 8.374710 11.609290 17.710724
v 6.185806 12.873054 17.710724
v 3.810715 13.737510 17.710724
v 1.321609 14.176414 17.710724
v -1.205917 14.176414 17.710724
v -3.695023 13.737510 17.710724
v -6.070114 12.873054 17.710724
v -8.259018 11.609290 17.710724
v -10.195206 9.984633 17.710724
v -11.819855 8.048446 17.710724
v -13.083618 5.859557 17.710724
v -13.948074 3.484466 17.710724
v -14.386978 0.995345 17.710724
v -14.386978 -1.532166 17.710724
v -13.948074 -4.021287 17.710724
v -13.083618 -6.396379 17.710724
v -11.819855 -8.585267 17.710724
v -10.195206 -10.521462 17.710724
v -8.259018 -12.146111 17.710724
v -6.070114 -13.409875 17.710724
v -3.695023 -14.274331 17.710724
v -1.205917 -14.713235 17.710724
v 1.321609 -14.713235 17.710724
v 3.810715 -14.274331 17.710724
v 6.185806 -13.409875 17.710724
v 8.374710 -12.146111 17.710724
v 10.310898 -10.521462 17.710724
v 11.935547 -8.585267 17.710724
v 13.199310 -6.396379 17.710724
v 14.063766 -4.021287 17.710724
v 14.502670 -1.532166 17.710724
v 14.502670 0.995345 17.710724
v 14.063766 3.484466 17.710724
v 13.199310 5.859557 17.710724
v 11.935547 8.048446 17.710724
v -24.473114 -14.698662 -7.672059
v -14.164001 -8.634361 -4.998246
v -24.952278 -14.879128 -7.714234
v -25.320740 -14.903236 -7.653794
v -25.842163 -14.776787 -7.438279
v -26.075233 -14.647423 -7.282959
v -26.276474 -14.483971 -7.106919
v -26.433876 -14.305473 -6.928238
v -26.564789 -14.097206 -6.731186
v -28.292801 -10.078651 -3.102204
v -29.069946 -7.449745 -0.804795
v -29.602509 -4.769913 1.480774
v -29.616707 -4.453499 1.740066
v -29.563736 -4.139687 1.982696
v -29.446053 -3.844673 2.196045
v -29.269058 -3.581253 2.370941
v -24.958435 0.822456 5.001587
v -20.512772 4.196159 6.768890
v -17.587646 5.936790 7.543702
v -14.544586 7.413970 8.079590
v -15.636505 -5.361275 -2.028351
v -16.377289 -1.729980 1.072861
v -16.332291 1.632431 3.785828
v -15.720383 4.558349 6.022354
v -15.193619 6.027832 7.097977
v -0.173630 28.191147 -7.672057
v -0.076355 16.231041 -4.998245
v -0.090347 28.696358 -7.714232
v 0.073013 29.027504 -7.653792
v 0.443222 29.415840 -7.438277
v 0.671799 29.553009 -7.282958
v 0.913971 29.645561 -7.106917
v 1.147263 29.692619 -6.928236
v 1.393082 29.701859 -6.731184
v 5.737259 29.189087 -3.102202
v 8.402527 28.547668 -0.804793
v 10.989609 27.668961 1.480775
v 11.264038 27.527451 1.733705
v 11.503677 27.332748 1.970002
v 11.707901 27.078369 2.190553
v 11.852295 26.785851 2.370942
v 13.510712 20.850891 5.001588
v 14.209579 15.313980 6.768891
v 14.254456 11.910431 7.543702
v 14.012207 8.536476 8.079590
v 11.725113 11.398849 5.606537
v 12.948349 10.031342 6.893784
v 3.403976 15.888741 -2.105758
v 6.797852 14.792213 0.880387
v 9.440994 13.303864 3.343613
v 17.590302 -24.009834 5.076766
v 11.765060 -22.527290 7.303939
v 6.076279 -20.110207 9.065459
v 3.336945 -18.547142 9.765334
v 0.705917 -16.755684 10.330947
v 17.915695 -24.031044 4.923827
v 18.237991 -23.981438 4.741241
v 18.527054 -23.871071 4.547484
v 18.786438 -23.704277 4.341872
v 25.345245 -16.409889 -4.035417
v 23.560455 -18.913368 -1.005235
v 21.371399 -21.380760 1.799026
v 25.509811 -16.059090 -4.438797
v 25.568222 -15.797142 -4.698685
v 25.565857 -15.391045 -5.040665
v 25.435196 -14.958260 -5.317322
v 25.141541 -14.542152 -5.461594
v 24.820282 -14.297722 -5.434464
v 14.413895 -8.401917 -2.760666
v 12.331528 -11.295952 1.016113
v 10.022125 -13.419823 3.841842
v 7.404373 -15.043144 6.215637
v 4.692200 -16.104225 8.133483
v 2.744232 -16.548271 9.282348
v -26.564789 -14.097206 -4.035416
v -27.840454 -11.299782 -1.005234
v -28.882759 -8.170319 1.799026
v -29.602509 -4.769913 4.341873
v -26.359169 -14.397499 -4.414933
v -26.178520 -14.570778 -4.659684
v -25.966812 -14.714439 -4.887894
v -25.532875 -14.875603 -5.221604
v -25.006462 -14.888359 -5.436310
v -24.473114 -14.698662 -5.434464
v -14.164001 -8.634361 -2.760666
v -15.629135 -5.383957 1.016113
v -16.313751 -2.322022 3.841843
v -16.410721 0.756683 6.215637
v -15.973541 3.636024 8.133484
v -15.384109 5.545043 9.282349
v -14.544586 7.413970 10.330948
v -29.269058 -3.581253 5.076767
v -25.051086 0.741157 7.313263
v -20.140625 4.436759 9.063889
v -17.419632 6.026771 9.763397
v -29.450127 -3.852448 4.923828
v -29.568314 -4.156357 4.741241
v -29.617264 -4.461891 4.547485
v 1.393082 29.701859 -4.035414
v 4.453552 29.407913 -1.005232
v 7.684891 28.745842 1.799028
v 10.989609 27.668961 4.341875
v 1.030212 29.673943 -4.414931
v 0.789810 29.604134 -4.659682
v 0.559555 29.492615 -4.887892
v 0.203003 29.197403 -5.221602
v -0.071243 28.747894 -5.436308
v -0.173630 28.191147 -5.434462
v -0.076355 16.231041 -2.760665
v 3.455994 15.877884 1.001084
v 6.437332 14.948395 3.816758
v 9.142349 13.505562 6.183777
v 10.465591 12.535385 7.302796
v 11.725113 11.398849 8.360581
v 12.935913 10.046898 9.387329
v 14.012207 8.536476 10.330948
v 11.852295 26.785851 5.076768
v 13.484100 20.984314 7.309098
v 14.231628 14.876953 9.062531
v 14.248306 11.715881 9.764298
v 11.707901 27.078369 4.923753
v 11.503677 27.332748 4.741090
v 11.263626 27.527794 4.547410
v -26.564789 -14.097206 -4.035416
v -26.359169 -14.397499 -4.414933
v -26.178520 -14.570778 -4.659684
v -25.966812 -14.714439 -4.887894
v -25.532875 -14.875603 -5.221604
v -25.006462 -14.888359 -5.436310
v -24.473114 -14.698662 -5.434464
v -26.564789 -14.097206 -6.731186
v -24.473114 -14.698662 -7.672059
v -24.952278 -14.879128 -7.714234
v -25.320740 -14.903236 -7.653794
v -25.842163 -14.776787 -7.438279
v -26.075233 -14.647423 -7.282959
v -26.276474 -14.483971 -7.106919
v -26.433876 -14.305473 -6.928238
v -29.269058 -3.581253 5.076767
v -29.450127 -3.852448 4.923828
v -29.568314 -4.156357 4.741241
v -29.617264 -4.461891 4.547485
v -29.602509 -4.769913 4.341873
v -29.269058 -3.581253 2.370941
v -29.602509 -4.769913 1.480774
v -29.616707 -4.453499 1.740066
v -29.563736 -4.139687 1.982696
v -29.446053 -3.844673 2.196045
v 1.393082 29.701859 -4.035414
v 1.030212 29.673943 -4.414931
v 0.789810 29.604134 -4.659682
v 0.559555 29.492615 -4.887892
v 0.203003 29.197403 -5.221602
v -0.071243 28.747894 -5.436308
v -0.173630 28.191147 -5.434462
v 1.393082 29.701859 -6.731184
v -0.173630 28.191147 -7.672057
v -0.090347 28.696358 -7.714232
v 0.073013 29.027504 -7.653792
v 0.443222 29.415840 -7.438277
v 0.671799 29.553009 -7.282958
v 0.913971 29.645561 -7.106917
v 1.147263 29.692619 -6.928236
v 11.503677 27.332748 4.741090
v 11.503677 27.332748 1.970002
v 11.852295 26.785851 5.076768
v 11.707901 27.078369 4.923753
v 11.852295 26.785851 2.370942
v 11.707901 27.078369 2.190553
v 17.590302 -24.009834 5.076766
v 17.915695 -24.031044 4.923827
v 18.237991 -23.981438 4.741241
v 18.527054 -23.871071 4.547484
v 18.786438 -23.704277 4.341872
v 17.590302 -24.009834 2.370940
v 18.786438 -23.704277 1.480773
v 18.519516 -23.874779 1.740065
v 18.221268 -23.985817 1.982695
v 17.906937 -24.031410 2.196044
v 25.141541 -14.542152 -5.461594
v 25.141541 -14.542152 -7.717591
v 25.345245 -16.409889 -4.035417
v 25.509811 -16.059090 -4.438797
v 25.568222 -15.797142 -4.698685
v 25.565857 -15.391045 -5.040665
v 25.435196 -14.958260 -5.317322
v 25.345245 -16.409889 -6.731187
v 25.400986 -14.890556 -7.664856
v 25.517975 -15.173012 -7.566773
v 25.580856 -15.609123 -7.345536
v 25.516418 -16.037804 -7.053223
vn 0.5474 0.8369 -0.0000
vn 0.3644 0.9312 -0.0000
vn 0.5470 0.8371 -0.0000
vn 0.7071 0.7071 -0.0000
vn -0.7071 -0.7071 -0.0000
vn -0.5736 -0.8192 -0.0000
vn -0.4226 -0.9063 -0.0000
vn -0.2588 -0.9659 -0.0000
vn -0.0872 -0.9962 -0.0000
vn 0.0392 -0.9992 -0.0000
vn 0.0872 -0.9962 -0.0000
vn 0.0393 -0.9992 -0.0000
vn 0.1317 -0.9913 -0.0000
vn 0.2248 -0.9744 -0.0000
vn 0.2588 -0.9659 -0.0000
vn 0.3969 -0.9179 -0.0000
vn 0.4227 -0.9063 -0.0001
vn 0.1628 -0.9867 -0.0000
vn 0.5747 -0.8184 -0.0000
vn 0.5735 -0.8192 -0.0000
vn 0.7071 -0.7071 -0.0000
vn 0.4226 -0.9063 -0.0000
vn 0.2809 -0.9597 -0.0000
vn 0.8192 -0.5736 -0.0000
vn 0.7429 -0.6694 -0.0000
vn 0.5736 -0.8192 -0.0000
vn 0.4453 -0.8954 -0.0000
vn 0.6039 -0.7970 -0.0000
vn 0.7439 -0.6683 -0.0000
vn 0.8701 -0.4929 -0.0000
vn 0.9063 -0.4226 -0.0000
vn 0.9659 -0.2588 -0.0000
vn 0.9962 -0.0872 -0.0000
vn 0.9962 0.0872 -0.0000
vn 0.9659 0.2588 -0.0000
vn 0.9063 0.4226 -0.0000
vn 0.8457 0.5336 -0.0000
vn 0.8192 0.5736 -0.0000
vn 0.7812 0.6242 -0.0000
vn 0.7805 0.6252 -0.0000
vn 0.1893 0.9819 -0.0000
vn 0.0445 0.9990 -0.0000
vn 0.1465 0.9892 -0.0000
vn 0.2781 0.9605 -0.0000
vn 0.2542 0.9671 -0.0000
vn -0.9450 -0.3270 -0.0000
vn -0.8874 -0.4610 -0.0000
vn -0.9299 -0.3677 -0.0000
vn -0.9709 -0.2394 -0.0000
vn -0.9647 -0.2634 -0.0000
vn -0.9887 -0.1500 -0.0000
vn -0.9887 -0.1501 -0.0000
vn 0.9810 0.1941 -0.0000
vn 0.9395 0.3425 -0.0000
vn 0.9803 0.1975 -0.0000
vn 0.9984 0.0557 -0.0000
vn 0.9990 0.0448 -0.0000
vn 0.9996 -0.0294 -0.0000
vn 0.9994 -0.0343 -0.0000
vn 0.9935 -0.1137 -0.0000
vn 0.5070 -0.8619 -0.0000
vn -1.0000 -0.0081 -0.0000
vn -0.6586 0.7525 -0.0000
vn -0.7664 0.6424 -0.0000
vn -0.6609 0.7504 -0.0000
vn -0.5475 0.8368 -0.0000
vn -0.5382 0.8428 -0.0000
vn -0.4743 0.8803 -0.0000
vn -0.4702 0.8826 -0.0000
vn -0.3983 0.9173 -0.0000
vn 0.7557 -0.6549 -0.0000
vn 0.8429 -0.5381 -0.0000
vn 0.7834 -0.6215 -0.0000
vn 0.6928 -0.7212 -0.0000
vn 0.7104 -0.7037 -0.0000
vn 0.6243 -0.7812 -0.0000
vn -0.3223 -0.9466 -0.0000
vn -0.1732 -0.9849 -0.0000
vn -0.1731 -0.9849 -0.0000
vn -0.3188 -0.9478 -0.0000
vn -0.4510 -0.8925 -0.0000
vn -0.4610 -0.8874 -0.0000
vn -0.5252 -0.8510 -0.0000
vn -0.5295 -0.8483 -0.0000
vn -0.5953 -0.8035 -0.0000
vn 0.4929 0.8701 -0.0000
vn -0.4543 -0.4543 -0.7663
vn -0.4543 -0.4544 -0.7662
vn -0.4543 -0.4542 -0.7664
vn -0.4542 -0.4543 -0.7663
vn -0.4545 -0.4543 -0.7662
vn -0.4542 -0.4543 -0.7664
vn 0.6308 0.7760 -0.0000
vn 0.5687 0.8225 -0.0000
vn 0.5736 0.8192 0.0001
vn 0.4085 0.9128 -0.0000
vn 0.4227 0.9063 -0.0000
vn 0.2588 0.9659 -0.0000
vn 0.5736 0.8192 -0.0000
vn 0.5506 0.8348 -0.0000
vn 0.4226 0.9063 -0.0000
vn 0.3866 0.9222 -0.0000
vn 0.2028 0.9792 -0.0000
vn 0.0872 0.9962 -0.0000
vn 0.2059 0.9786 -0.0000
vn -0.0081 1.0000 -0.0000
vn -0.0872 0.9962 -0.0000
vn -0.2588 0.9659 -0.0000
vn -0.4226 0.9063 -0.0000
vn -0.5736 0.8192 -0.0000
vn -0.7071 0.7071 -0.0000
vn -0.8191 0.5736 -0.0000
vn -0.8850 0.4656 -0.0000
vn -0.9063 0.4226 -0.0000
vn -0.9243 0.3816 -0.0000
vn -0.9563 0.2925 -0.0000
vn -0.9659 0.2588 -0.0000
vn -0.9933 0.1152 -0.0000
vn -0.9962 0.0871 -0.0000
vn -0.9359 0.3523 -0.0000
vn -0.9961 -0.0886 -0.0000
vn -0.9962 -0.0874 -0.0000
vn -0.9659 -0.2588 -0.0000
vn -0.9962 0.0872 -0.0000
vn -0.9716 0.2366 -0.0000
vn -0.9063 -0.4226 -0.0000
vn -0.9512 -0.3086 -0.0000
vn -0.9962 -0.0872 -0.0000
vn -0.9981 0.0621 -0.0000
vn -0.9922 -0.1245 -0.0000
vn -0.9507 -0.3100 -0.0000
vn -0.8619 -0.5070 -0.0000
vn -0.8191 -0.5736 -0.0000
vn -0.0000 -0.0000 -1.0000
vn 0.0001 -0.0000 -1.0000
vn -0.0001 -0.0000 -1.0000
vn -0.0000 -0.0000 1.0000
vn -0.1663 0.6205 -0.7663
vn -0.1663 0.6204 -0.7665
vn -0.1663 0.6205 -0.7664
vn -0.1663 0.6206 -0.7663
vn -0.1662 0.6206 -0.7663
vn -0.1664 0.6205 -0.7663
vn -0.1661 0.6206 -0.7663
vn -0.1664 0.6205 -0.7664
vn 0.6205 -0.1663 -0.7663
vn 0.6206 -0.1663 -0.7663
vn 0.6206 -0.1662 -0.7663
vn 0.6205 -0.1662 -0.7664
vn 0.6205 -0.1663 -0.7664
vn 0.6204 -0.1663 -0.7665
vn 0.4927 0.5725 0.6553
vn 0.4939 0.5767 0.6508
vn 0.4942 0.5777 0.6496
vn 0.4910 0.5665 0.6618
vn 0.4890 0.5598 0.6689
vn 0.4876 0.5549 0.6741
vn 0.4853 0.5475 0.6817
vn 0.4736 0.5104 0.7178
vn 0.3989 0.3133 0.8618
vn 0.4197 0.3637 0.8316
vn 0.4098 0.3393 0.8467
vn 0.4009 0.3180 0.8592
vn 0.3988 0.3131 0.8619
vn 0.4359 0.4049 0.8037
vn 0.4667 0.4899 0.7363
vn 0.4454 0.4301 0.7852
vn 0.4544 0.4547 0.7660
vn 0.4041 0.3257 0.8547
vn 0.4222 0.3698 0.8277
vn 0.4159 0.3543 0.8376
vn 0.4202 0.3648 0.8309
vn 0.4184 0.3605 0.8336
vn 0.4170 0.3569 0.8359
vn 0.2479 -0.7113 0.6577
vn 0.2517 -0.7153 0.6519
vn 0.2532 -0.7169 0.6496
vn 0.2429 -0.7062 0.6651
vn 0.2397 -0.7029 0.6697
vn 0.2364 -0.6994 0.6745
vn 0.2315 -0.6941 0.6817
vn 0.2532 -0.7168 0.6496
vn 0.2052 -0.6653 0.7178
vn 0.0718 -0.5021 0.8618
vn 0.1051 -0.5454 0.8316
vn 0.0890 -0.5246 0.8467
vn 0.0749 -0.5062 0.8592
vn 0.0717 -0.5019 0.8619
vn 0.1327 -0.5800 0.8037
vn 0.1909 -0.6492 0.7363
vn 0.1497 -0.6008 0.7853
vn 0.1665 -0.6209 0.7660
vn 0.0799 -0.5128 0.8548
vn 0.1092 -0.5505 0.8276
vn 0.0989 -0.5373 0.8376
vn 0.1059 -0.5463 0.8309
vn 0.1030 -0.5426 0.8336
vn 0.1006 -0.5395 0.8359
vn -0.7400 0.1410 0.6577
vn -0.7453 0.1397 0.6519
vn -0.7474 0.1391 0.6496
vn -0.7330 0.1427 0.6651
vn -0.7286 0.1438 0.6697
vn -0.7239 0.1449 0.6745
vn -0.7169 0.1466 0.6816
vn -0.6791 0.1549 0.7175
vn -0.4707 0.1888 0.8618
vn -0.5196 0.1824 0.8347
vn -0.4964 0.1856 0.8480
vn -0.4758 0.1882 0.8592
vn -0.4706 0.1889 0.8619
vn -0.5439 0.1789 0.8199
vn -0.6576 0.1593 0.7363
vn -0.5952 0.1707 0.7852
vn -0.6215 0.1661 0.7656
vn -0.4841 0.1871 0.8548
vn -0.5694 0.1750 0.8033
vn -0.5314 0.1807 0.8276
vn -0.5148 0.1831 0.8376
vn -0.5261 0.1814 0.8309
vn -0.5215 0.1821 0.8336
vn -0.5175 0.1827 0.8359
vn 0.1876 -0.9822 -0.0000
vn 0.5070 -0.8620 -0.0000
vn 0.1515 -0.9885 -0.0000
vn -0.0580 -0.9983 -0.0000
vn -0.1995 -0.9799 -0.0000
vn -0.4056 -0.9140 -0.0000
vn -0.4887 -0.8724 -0.0000
vn -0.5610 -0.8278 -0.0000
vn -0.6299 -0.7767 -0.0000
vn -0.6952 -0.7188 -0.0000
vn -0.7503 -0.6611 -0.0000
vn -0.8002 -0.5998 -0.0000
vn -0.9981 0.0609 -0.0000
vn -0.9985 0.0553 -0.0000
vn -0.9628 0.2701 -0.0000
vn -0.9659 0.2590 -0.0000
vn -0.8844 0.4668 -0.0000
vn -0.8871 0.4616 -0.0000
vn -0.9445 0.3286 -0.0000
vn -0.9318 0.3630 -0.0000
vn -0.8355 0.5494 -0.0000
vn -0.7489 0.6627 -0.0000
vn -0.5887 0.8083 -0.0000
vn -0.5112 0.8595 -0.0000
vn -0.4363 0.8998 -0.0000
vn -0.3577 0.9339 -0.0000
vn -0.2749 0.9615 -0.0000
vn -0.1974 0.9803 -0.0000
vn -0.1194 0.9929 -0.0000
vn 0.8432 0.5375 -0.0000
vn 0.8433 0.5375 -0.0000
vn 0.4463 -0.8949 -0.0000
vn 0.4513 -0.8924 -0.0000
vn 0.6242 -0.7812 -0.0000
vn 0.2475 -0.9689 -0.0000
vn 0.2586 -0.9660 -0.0000
vn 0.0380 -0.9993 -0.0000
vn 0.0438 -0.9990 -0.0000
vn 0.8801 0.4749 -0.0000
vn 0.9030 0.4297 -0.0000
vn 0.9581 0.2865 -0.0000
vn 0.9900 0.1412 -0.0000
vn 1.0000 -0.0042 -0.0000
vn 0.9916 -0.1296 -0.0000
vn 0.9570 -0.2900 -0.0000
vn 0.9526 -0.3042 -0.0000
vn 0.8429 -0.5380 -0.0000
vt 6.076976 15.977031
vt 5.870767 13.368848
vt 6.076623 13.163319
vt 5.870767 16.229956
vt 6.283185 15.740734
vt 6.283185 12.969635
vt 0.000000 30.000000
vt 0.000000 0.000000
vt 0.174533 0.000000
vt 0.174533 30.000000
vt 0.349066 0.000000
vt 0.349066 30.000000
vt 0.523599 0.000000
vt 0.523599 30.000000
vt 0.698132 0.000000
vt 0.698132 30.000000
vt 0.824686 20.368864
vt 0.872665 0.000000
vt 0.824686 22.620220
vt 0.917481 19.387249
vt 0.872665 30.000000
vt 1.012124 18.311619
vt 1.047198 0.000000
vt 1.193538 16.075102
vt 1.221730 0.000000
vt 1.047198 30.000000
vt 0.948937 21.571621
vt 1.397693 13.362126
vt 1.396263 0.000000
vt 1.570796 0.000000
vt 1.221730 30.000000
vt 1.070099 20.422758
vt 1.745329 0.000000
vt 1.622779 10.260923
vt 1.396263 30.000000
vt 1.246832 18.504904
vt 1.433782 16.131117
vt 1.570796 30.000000
vt 1.624225 13.305383
vt 1.840729 7.291020
vt 1.919862 0.000000
vt 1.840729 9.528608
vt 2.094395 0.000000
vt 1.745329 30.000000
vt 1.919862 30.000000
vt 2.094395 30.000000
vt 2.268928 30.000000
vt 2.268928 0.000000
vt 2.443461 0.000000
vt 2.443461 30.000000
vt 2.617994 0.000000
vt 2.617994 30.000000
vt 2.792527 0.000000
vt 2.792527 30.000000
vt 2.919081 20.368864
vt 2.967060 0.000000
vt 2.919081 22.620220
vt 3.030337 19.183056
vt 3.141593 0.000000
vt 2.967060 30.000000
vt 3.031544 21.676601
vt 3.141593 17.895811
vt 3.141593 30.000000
vt 3.141593 20.649857
vt 5.688250 20.812925
vt 5.542310 24.441912
vt 5.542310 21.746149
vt 5.644839 18.715967
vt 5.779661 18.515530
vt 5.754844 15.911709
vt 3.593855 20.812925
vt 3.447915 24.441912
vt 3.447915 21.746149
vt 3.550444 18.715967
vt 3.685266 18.515530
vt 3.660449 15.911709
vt 3.776372 16.229956
vt 3.776372 13.368848
vt 0.590023 12.709135
vt 0.435812 15.339780
vt 0.435812 12.633968
vt 0.586621 10.401636
vt 0.729657 10.941843
vt 0.740597 8.648190
vt 0.814779 10.167034
vt 0.819645 7.946428
vt 0.899370 9.631136
vt 0.899370 7.379780
vt -16.500000 22.708981
vt -28.460499 23.145197
vt -28.460499 25.382784
vt -16.500000 20.471392
vt 4.778813 12.709135
vt 4.624602 15.339780
vt 4.624602 12.633968
vt 4.775731 10.397463
vt 4.918447 10.941843
vt 4.929526 8.646839
vt 5.003569 10.167034
vt 5.008334 7.947338
vt 5.088161 9.631136
vt 5.088161 7.379780
vt 1.499460 20.812925
vt 1.353519 21.746149
vt 1.456049 18.715967
vt 1.353519 24.441912
vt 1.590871 18.515530
vt 1.566054 15.911709
vt 1.681977 16.229956
vt 1.681977 13.368848
vt 2.684418 12.709135
vt 2.530207 15.339780
vt 2.530207 12.633968
vt 2.680622 10.406786
vt 2.824052 10.941843
vt 2.835300 8.645272
vt 2.909174 10.167034
vt 2.914169 7.945392
vt 2.993765 9.631136
vt 2.993765 7.379780
vt -1.561402 -24.561792
vt -2.395566 -27.883482
vt -0.867614 -26.897799
vt 0.806680 -26.008663
vt -0.355358 -21.285828
vt 4.287972 -24.660313
vt 2.395554 -16.118465
vt 8.510908 -23.746593
vt 6.490335 -10.814960
vt 7.094687 -10.385788
vt 6.762589 -10.575814
vt 7.472341 -10.253404
vt 7.875956 -10.185225
vt 11.433608 -10.006044
vt 13.338146 -23.522287
vt 15.009665 -10.076301
vt 17.961006 -24.097485
vt 22.122967 -12.570089
vt 20.658434 -10.705358
vt 21.159706 -10.847424
vt 22.111771 -11.740279
vt 22.193846 -12.170090
vt 21.959097 -11.457820
vt 21.614719 -11.104981
vt 3.244455 19.592070
vt 3.322096 15.632891
vt 3.316126 0.000000
vt 3.506197 13.169655
vt 3.490659 0.000000
vt 3.665191 0.000000
vt 3.316126 30.000000
vt 3.343937 18.473045
vt 3.490659 30.000000
vt 3.530010 16.106030
vt 3.722779 10.183515
vt 3.839724 0.000000
vt 3.665191 30.000000
vt 3.719558 13.290359
vt 3.935124 7.291020
vt 4.014257 0.000000
vt 3.935124 9.528608
vt 4.188790 0.000000
vt 3.839724 30.000000
vt 4.014257 30.000000
vt 4.188790 30.000000
vt 4.363323 0.000000
vt 4.363323 30.000000
vt 4.537856 0.000000
vt 4.537856 30.000000
vt 4.712389 0.000000
vt 4.712389 30.000000
vt 4.886922 0.000000
vt 4.886922 30.000000
vt 5.013476 20.368864
vt 5.061455 0.000000
vt 5.013476 22.620220
vt 5.106271 19.387249
vt 5.061455 30.000000
vt 5.200914 18.311619
vt 5.235988 0.000000
vt 5.382328 16.075102
vt 5.410521 0.000000
vt 5.235988 30.000000
vt 5.137727 21.571621
vt 5.586483 13.362126
vt 5.585053 0.000000
vt 5.759586 0.000000
vt 5.410521 30.000000
vt 5.258889 20.422758
vt 5.934119 0.000000
vt 5.811569 10.260923
vt 5.585053 30.000000
vt 5.435622 18.504904
vt 5.622572 16.131117
vt 5.759586 30.000000
vt 5.813015 13.305383
vt 6.029520 7.291020
vt 6.108653 0.000000
vt 6.029520 9.528608
vt 6.283185 0.000000
vt 5.934119 30.000000
vt 6.108653 30.000000
vt 6.283185 30.000000
vt -1.124878 -10.340578
vt -5.643332 -15.504929
vt -2.865195 -16.249329
vt -1.340578 -10.124878
vt -0.875000 -10.515545
vt -1.515544 -9.875000
vt -1.644462 -9.598536
vt -8.250000 -14.289419
vt -0.598535 -10.644462
vt -1.723414 -9.303885
vt -0.303884 -10.723413
vt 0.000000 -16.500000
vt -1.750000 -9.000000
vt -10.605995 -12.639733
vt 0.000000 -10.750000
vt -1.723414 -8.696115
vt 0.303884 -10.723413
vt 2.865195 -16.249329
vt 0.598535 -10.644462
vt 0.875000 -10.515545
vt 1.124878 -10.340578
vt 5.643332 -15.504929
vt 1.340578 -10.124878
vt 1.515544 -9.875000
vt 1.644462 -9.598536
vt -3.535332 -4.213244
vt -12.639733 -10.605995
vt -1.644462 -8.401464
vt -4.213244 -3.535332
vt -4.763140 -2.750000
vt -14.289419 -8.250000
vt -2.750000 -4.763140
vt -1.515544 -8.125000
vt -1.881111 -5.168309
vt -1.124878 -7.659422
vt -0.875000 -7.484456
vt -1.340578 -7.875122
vt -5.168309 -1.881111
vt -15.504929 -5.643332
vt -16.249329 -2.865195
vt -5.416443 -0.955065
vt -0.955065 -5.416443
vt -0.598535 -7.355538
vt -0.303884 -7.276587
vt 8.250000 -14.289419
vt 1.723414 -9.303885
vt 1.750000 -9.000000
vt -5.500000 -0.000000
vt -16.500000 -0.000000
vt -0.000000 -5.500000
vt 0.000000 -7.250000
vt 0.303884 -7.276587
vt 0.955065 -5.416443
vt 0.598535 -7.355538
vt 0.875000 -7.484456
vt -5.416443 0.955065
vt -16.249329 2.865195
vt 1.881111 -5.168309
vt 1.340578 -7.875122
vt 1.515544 -8.125000
vt 1.124878 -7.659422
vt -5.168309 1.881111
vt -15.504929 5.643332
vt 10.605995 -12.639733
vt 1.723414 -8.696115
vt 2.750000 -4.763140
vt 1.644462 -8.401464
vt -4.763140 2.750000
vt -14.289419 8.250000
vt -12.639733 10.605995
vt 3.535332 -4.213244
vt -4.213244 3.535332
vt -10.605995 12.639733
vt -3.535332 4.213244
vt 12.639733 -10.605995
vt 4.213244 -3.535332
vt 14.289419 -8.250000
vt 4.763140 -2.750000
vt -1.124878 7.659422
vt -1.340578 7.875122
vt -1.881111 5.168309
vt -1.515544 8.125000
vt -2.750000 4.763140
vt -0.875000 7.484456
vt -0.955065 5.416443
vt -1.644462 8.401464
vt -0.598535 7.355538
vt -1.723414 8.696115
vt -0.303884 7.276587
vt -0.000000 5.500000
vt -1.750000 9.000000
vt -8.250000 14.289419
vt -0.000000 7.250000
vt 0.303884 7.276587
vt 0.955065 5.416443
vt -1.723414 9.303885
vt -1.644462 9.598536
vt 0.598535 7.355538
vt 0.875000 7.484456
vt 1.881111 5.168309
vt 1.124878 7.659422
vt 1.340578 7.875122
vt 1.515544 8.125000
vt 2.750000 4.763140
vt -5.643332 15.504929
vt -1.340578 10.124878
vt -1.124878 10.340578
vt -1.515544 9.875000
vt 15.504929 -5.643332
vt 5.168309 -1.881111
vt 1.644462 8.401464
vt 3.535332 4.213244
vt 1.723414 8.696115
vt -2.865195 16.249329
vt -0.598535 10.644462
vt -0.303884 10.723413
vt -0.875000 10.515545
vt 16.249329 -2.865195
vt 5.416443 -0.955065
vt -0.000000 16.500000
vt -0.000000 10.750000
vt 0.303884 10.723413
vt 16.500000 0.000000
vt 5.500000 0.000000
vt 2.865195 16.249329
vt 0.875000 10.515545
vt 1.124878 10.340578
vt 0.598535 10.644462
vt 16.249329 2.865195
vt 5.416443 0.955065
vt 5.168309 1.881111
vt 5.643332 15.504929
vt 1.515544 9.875000
vt 1.644462 9.598536
vt 1.340578 10.124878
vt 15.504929 5.643332
vt 4.763140 2.750000
vt 8.250000 14.289419
vt 1.723414 9.303885
vt 1.750000 9.000000
vt 14.289419 8.250000
vt 10.605995 12.639733
vt 12.639733 10.605995
vt 4.213244 3.535332
vt -11.107644 -9.320420
vt -9.320420 -11.107644
vt -12.557368 -7.250000
vt -7.250000 -12.557368
vt -13.625543 -4.959292
vt -4.959292 -13.625543
vt -14.279713 -2.517899
vt -2.517899 -14.279713
vt -14.500000 -0.000000
vt 0.000000 -14.500000
vt -14.279713 2.517899
vt 2.517899 -14.279713
vt -13.625543 4.959292
vt 4.959292 -13.625543
vt -12.557368 7.250000
vt 7.250000 -12.557368
vt -11.107644 9.320420
vt 9.320420 -11.107644
vt 11.107644 -9.320420
vt -9.320420 11.107644
vt 12.557368 -7.250000
vt -7.250000 12.557368
vt 13.625543 -4.959292
vt -4.959292 13.625543
vt -2.517899 14.279713
vt 14.279713 -2.517899
vt -0.000000 14.500000
vt 14.500000 0.000000
vt 2.517899 14.279713
vt 14.279713 2.517899
vt 4.959292 13.625543
vt 13.625543 4.959292
vt 7.250000 12.557368
vt 12.557368 7.250000
vt 9.320420 11.107644
vt 11.107644 9.320420
vt -25.317205 2.544009
vt -25.171072 2.051469
vt -24.938520 1.758354
vt -24.441193 1.463434
vt -24.142551 1.385991
vt -23.830446 1.357785
vt -23.533268 1.373539
vt -23.223413 1.431299
vt -17.803154 3.141588
vt -26.175249 14.769660
vt -21.714964 16.114109
vt -14.504464 4.524252
vt -10.311193 7.264100
vt -11.323529 6.127577
vt -10.982014 6.353232
vt -10.690217 6.627099
vt -10.463404 6.935246
vt -17.391266 18.272387
vt -8.712417 13.770889
vt -13.899138 20.816620
vt -8.287510 19.609434
vt -11.261093 23.458242
vt -8.510088 23.093246
vt -10.089724 24.948784
vt -9.091248 26.468407
vt -11.365858 -21.829725
vt -13.472684 -24.529861
vt -11.311903 -24.208031
vt -9.073197 -24.100309
vt -8.937452 -19.321871
vt -5.346680 -24.383379
vt -4.331002 -15.709424
vt -1.535458 -25.245634
vt 1.559487 -12.516223
vt 2.307464 -12.368168
vt 1.915470 -12.405624
vt 2.694822 -12.401725
vt 3.081419 -12.500975
vt 6.407351 -13.776581
vt 2.788347 -26.961016
vt 9.649189 -15.287742
vt 15.145210 -20.446404
vt 6.675031 -29.304104
vt 15.471918 -19.637753
vt 15.411417 -20.006990
vt 15.355675 -19.071360
vt 14.560402 -18.148561
vt 15.212124 -18.798271
vt 14.811547 -18.339012
vt 15.023082 -18.548336
vt 3.877834 61.311840
vt 3.871537 60.893780
vt 3.869956 60.497498
vt 3.886804 61.570618
vt 3.896821 61.693375
vt 3.904056 61.713085
vt 3.914843 61.654110
vt 3.869956 48.241776
vt 3.967994 47.041885
vt 4.224015 40.984032
vt 4.161592 41.315605
vt 4.191961 39.624535
vt 4.218258 37.764812
vt 4.224226 44.214668
vt 4.109290 43.526485
vt 3.996431 60.681873
vt 4.076639 59.398323
vt 4.044139 45.486191
vt 4.208766 50.592091
vt 4.153948 57.766415
vt 4.173393 56.737438
vt 4.160178 57.581554
vt 4.165603 57.346928
vt 4.170183 57.057308
vt 3.881097 67.319443
vt 3.873065 66.929802
vt 3.869956 66.386894
vt 3.891368 67.531898
vt 3.897924 67.589119
vt 3.904709 67.601936
vt 3.914843 67.543503
vt 3.869956 54.131168
vt 3.967994 52.931278
vt 4.224022 46.882832
vt 4.161592 47.204998
vt 4.191961 45.513931
vt 4.218258 43.654205
vt 4.224223 50.111000
vt 4.109290 49.415878
vt 3.996431 66.571266
vt 4.076639 65.287720
vt 4.044139 51.375587
vt 4.208886 56.452095
vt 4.153948 63.655807
vt 4.173393 62.626831
vt 4.160178 63.470947
vt 4.165603 63.236324
vt 4.170183 62.946701
vt 3.881097 74.504562
vt 3.873065 74.114922
vt 3.869956 73.572014
vt 3.891368 74.717026
vt 3.897924 74.774239
vt 3.904709 74.787056
vt 3.914843 74.728622
vt 3.869956 61.316288
vt 3.967596 60.122921
vt 4.224020 54.063801
vt 4.167682 54.080685
vt 4.194669 52.527721
vt 4.218258 50.839325
vt 4.224218 57.301842
vt 4.139081 55.430580
vt 3.996431 73.756386
vt 4.076639 72.472839
vt 4.043454 58.577896
vt 4.208832 63.650372
vt 4.108411 56.631989
vt 4.153948 70.840927
vt 4.173393 69.811951
vt 4.160176 70.656158
vt 4.165598 70.421654
vt 4.170181 70.131935
vt 2.167493 25.424961
vt 1.824462 23.145197
vt 2.204137 23.147039
vt 1.824462 25.382784
vt 2.414285 25.364527
vt 2.557019 22.932327
vt 2.773906 25.149006
vt 2.866855 22.598618
vt 2.951853 24.993685
vt 3.037623 22.370415
vt 3.124912 24.817654
vt 3.204693 22.125654
vt 3.283732 24.638966
vt 3.987920 15.970658
vt 3.982313 13.163236
vt 4.200487 15.728039
vt 4.188960 12.969482
vt 4.412629 15.514687
vt 4.406778 12.786903
vt 4.261888 25.424961
vt 3.918857 23.145197
vt 4.298532 23.147039
vt 3.918857 25.382784
vt 4.508680 25.364527
vt 4.651414 22.932327
vt 4.868301 25.149006
vt 4.961251 22.598618
vt 5.046248 24.993685
vt 5.132018 22.370415
vt 5.219307 24.817654
vt 5.299088 22.125654
vt 5.378127 24.638966
vt 0.217906 15.520173
vt 0.000000 15.740734
vt 0.000000 12.969635
vt 0.217904 12.786969
vt 1.893525 15.970658
vt 1.887918 13.163236
vt 2.106092 15.728039
vt 2.094565 12.969482
vt 2.318234 15.514687
vt 2.312383 12.786903
vt 0.290614 25.375591
vt 0.000000 25.428320
vt 0.000000 23.172319
vt 0.341203 23.028051
vt 0.494789 25.277508
vt 0.643748 22.751389
vt 0.789600 25.056267
vt 0.915318 22.409412
vt 1.079617 24.763948
vt 1.094472 22.149519
s 1
usemtl mat_9
f 6/1/1 3/2/2 2/3/3
f 6/1/1 5/4/2 3/2/2
f 4/5/4 2/3/3 1/6/4
f 4/5/4 6/1/1 2/3/3
f 50/7/5 7/8/5 8/9/6
f 49/10/6 8/9/6 9/11/7
f 49/10/6 50/7/5 8/9/6
f 48/12/7 9/11/7 10/13/8
f 48/12/7 49/10/6 9/11/7
f 47/14/8 10/13/8 11/15/9
f 47/14/8 48/12/7 10/13/8
f 46/16/9 47/14/8 11/15/9
f 52/17/10 11/15/9 12/18/11
f 52/17/10 46/16/9 11/15/9
f 51/19/12 46/16/9 52/17/10
f 64/20/13 52/17/10 12/18/11
f 45/21/11 46/16/9 51/19/12
f 63/22/14 12/18/11 13/23/15
f 63/22/14 64/20/13 12/18/11
f 62/24/16 13/23/15 14/25/17
f 44/26/15 45/21/11 58/27/18
f 61/28/19 14/25/17 15/29/20
f 16/30/21 61/28/19 15/29/20
f 43/31/22 44/26/15 57/32/23
f 17/33/24 60/34/25 16/30/21
f 42/35/26 43/31/22 56/36/27
f 42/35/26 56/36/27 55/37/28
f 41/38/21 42/35/26 55/37/28
f 41/38/21 55/37/28 54/39/29
f 59/40/30 17/33/24 18/41/31
f 53/42/30 59/40/30 18/41/31
f 19/43/32 53/42/30 18/41/31
f 40/44/24 41/38/21 54/39/29
f 40/44/24 54/39/29 53/42/30
f 39/45/31 40/44/24 53/42/30
f 38/46/32 53/42/30 19/43/32
f 38/46/32 39/45/31 53/42/30
f 37/47/33 19/43/32 20/48/33
f 37/47/33 20/48/33 21/49/34
f 37/47/33 38/46/32 19/43/32
f 36/50/34 21/49/34 22/51/35
f 36/50/34 37/47/33 21/49/34
f 35/52/35 22/51/35 23/53/36
f 35/52/35 36/50/34 22/51/35
f 34/54/36 35/52/35 23/53/36
f 28/55/37 23/53/36 24/56/38
f 28/55/37 34/54/36 23/53/36
f 29/57/37 34/54/36 28/55/37
f 27/58/39 24/56/38 25/59/4
f 27/58/39 28/55/37 24/56/38
f 33/60/38 29/57/37 31/61/40
f 33/60/38 34/54/36 29/57/37
f 26/62/4 27/58/39 25/59/4
f 32/63/4 31/61/40 30/64/4
f 32/63/4 33/60/38 31/61/40
f 57/32/23 56/36/27 43/31/22
f 58/27/18 57/32/23 44/26/15
f 51/19/12 58/27/18 45/21/11
f 59/40/30 60/34/25 17/33/24
f 60/34/25 61/28/19 16/30/21
f 61/28/19 62/24/16 14/25/17
f 62/24/16 63/22/14 13/23/15
f 66/65/41 65/66/42 69/67/42
f 66/65/41 69/67/42 70/68/43
f 67/69/44 70/68/43 71/70/45
f 67/69/44 66/65/41 70/68/43
f 68/4/2 71/70/45 72/2/2
f 68/4/2 67/69/44 71/70/45
f 74/71/46 73/72/47 77/73/47
f 74/71/46 77/73/47 78/74/48
f 75/75/49 78/74/48 79/76/50
f 75/75/49 74/71/46 78/74/48
f 76/77/51 79/76/50 80/78/52
f 76/77/51 75/75/49 79/76/50
f 82/79/53 81/80/54 86/81/54
f 82/79/53 86/81/54 87/82/55
f 83/83/56 87/82/55 88/84/57
f 83/83/56 82/79/53 87/82/55
f 84/85/58 88/84/57 89/86/59
f 84/85/58 83/83/56 88/84/57
f 85/87/60 89/86/59 90/88/60
f 85/87/60 84/85/58 89/86/59
f 92/89/61 94/90/61 93/91/61
f 92/89/61 91/92/61 94/90/61
f 96/89/62 98/90/62 97/91/62
f 96/89/62 95/92/62 98/90/62
f 100/93/63 99/94/64 104/95/64
f 100/93/63 104/95/64 105/96/65
f 101/97/66 105/96/65 106/98/67
f 101/97/66 100/93/63 105/96/65
f 102/99/68 106/98/67 107/100/69
f 102/99/68 101/97/66 106/98/67
f 103/101/70 107/100/69 108/102/70
f 103/101/70 102/99/68 107/100/69
f 115/103/71 109/104/72 110/105/73
f 115/103/71 114/106/72 109/104/72
f 116/107/74 110/105/73 111/108/75
f 116/107/74 115/103/71 110/105/73
f 113/109/76 111/108/75 112/110/76
f 113/109/76 116/107/74 111/108/75
f 118/111/77 117/112/78 122/113/79
f 118/111/77 122/113/79 123/114/80
f 119/115/81 123/114/80 124/116/82
f 119/115/81 118/111/77 123/114/80
f 120/117/83 124/116/82 125/118/84
f 120/117/83 119/115/81 124/116/82
f 121/119/85 125/118/84 126/120/85
f 121/119/85 120/117/83 125/118/84
f 128/89/86 130/90/86 129/91/86
f 128/89/86 127/92/86 130/90/86
f 141/121/87 142/122/87 148/123/87
f 147/124/87 141/121/87 148/123/87
f 140/125/87 141/121/87 147/124/87
f 146/126/87 140/125/87 147/124/87
f 139/127/87 146/126/87 145/128/87
f 139/127/87 140/125/87 146/126/87
f 138/129/87 139/127/87 145/128/87
f 136/130/88 137/131/89 138/129/87
f 135/132/90 136/130/88 138/129/87
f 134/133/87 135/132/90 138/129/87
f 133/134/87 145/128/87 144/135/87
f 133/134/87 138/129/87 145/128/87
f 133/134/87 134/133/87 138/129/87
f 132/136/87 144/135/87 143/137/87
f 132/136/87 133/134/87 144/135/87
f 149/138/87 132/136/87 143/137/87
f 131/139/87 132/136/87 149/138/87
f 154/140/87 131/139/87 149/138/87
f 151/141/89 149/138/87 150/142/91
f 152/143/92 149/138/87 151/141/89
f 153/144/90 154/140/87 149/138/87
f 153/144/90 149/138/87 152/143/92
f 193/63/4 194/64/4 199/145/93
f 203/146/94 155/59/4 157/147/95
f 202/148/96 157/147/95 158/149/97
f 202/148/96 203/146/94 157/147/95
f 159/150/98 202/148/96 158/149/97
f 192/151/99 199/145/93 198/152/100
f 192/151/99 193/63/4 199/145/93
f 191/153/101 198/152/100 197/154/102
f 191/153/101 192/151/99 198/152/100
f 201/155/103 159/150/98 160/156/104
f 201/155/103 202/148/96 159/150/98
f 190/157/98 197/154/102 196/158/105
f 190/157/98 191/153/101 197/154/102
f 200/159/106 160/156/104 161/160/107
f 195/161/106 200/159/106 161/160/107
f 162/162/108 195/161/106 161/160/107
f 189/163/104 196/158/105 195/161/106
f 189/163/104 190/157/98 196/158/105
f 188/164/107 189/163/104 195/161/106
f 187/165/108 195/161/106 162/162/108
f 187/165/108 188/164/107 195/161/106
f 187/165/108 162/162/108 163/166/109
f 186/167/109 163/166/109 164/168/110
f 186/167/109 187/165/108 163/166/109
f 185/169/110 164/168/110 165/170/111
f 185/169/110 186/167/109 164/168/110
f 184/171/111 165/170/111 166/172/112
f 184/171/111 185/169/110 165/170/111
f 183/173/112 184/171/111 166/172/112
f 217/174/113 166/172/112 167/175/114
f 217/174/113 183/173/112 166/172/112
f 210/176/113 183/173/112 217/174/113
f 216/177/115 217/174/113 167/175/114
f 182/178/114 183/173/112 210/176/113
f 215/179/116 167/175/114 168/180/117
f 215/179/116 216/177/115 167/175/114
f 214/181/118 168/180/117 169/182/119
f 181/183/117 182/178/114 209/184/120
f 213/185/121 169/182/119 170/186/122
f 171/187/123 213/185/121 170/186/122
f 180/188/124 181/183/117 208/189/125
f 172/190/126 212/191/127 171/187/123
f 179/192/128 207/193/129 206/194/130
f 179/192/128 180/188/124 207/193/129
f 178/195/123 206/194/130 205/196/131
f 178/195/123 179/192/128 206/194/130
f 211/197/132 172/190/126 173/198/133
f 204/199/132 211/197/132 173/198/133
f 174/200/5 204/199/132 173/198/133
f 177/201/126 205/196/131 204/199/132
f 177/201/126 178/195/123 205/196/131
f 176/202/133 177/201/126 204/199/132
f 175/203/5 204/199/132 174/200/5
f 175/203/5 176/202/133 204/199/132
f 200/159/106 201/155/103 160/156/104
f 203/146/94 156/62/4 155/59/4
f 208/189/125 207/193/129 180/188/124
f 209/184/120 208/189/125 181/183/117
f 210/176/113 209/184/120 182/178/114
f 211/197/132 212/191/127 172/190/126
f 212/191/127 213/185/121 171/187/123
f 213/185/121 214/181/118 169/182/119
f 214/181/118 215/179/116 168/180/117
f 313/204/134 247/205/134 246/206/134
f 313/204/134 312/207/134 247/205/134
f 314/208/134 313/204/134 246/206/134
f 311/209/134 247/205/134 312/207/134
f 310/210/134 248/211/134 247/205/134
f 310/210/134 247/205/134 311/209/134
f 315/212/134 314/208/134 246/206/134
f 309/213/134 248/211/134 310/210/134
f 316/214/134 246/206/134 245/215/134
f 316/214/134 315/212/134 246/206/134
f 308/216/134 249/217/134 248/211/134
f 308/216/134 248/211/134 309/213/134
f 317/218/134 316/214/134 245/215/134
f 307/219/134 249/217/134 308/216/134
f 318/220/134 245/215/134 244/221/134
f 318/220/134 317/218/134 245/215/134
f 319/222/134 318/220/134 244/221/134
f 320/223/134 319/222/134 244/221/134
f 321/224/134 244/221/134 243/225/134
f 321/224/134 320/223/134 244/221/134
f 322/226/134 321/224/134 243/225/134
f 323/227/134 322/226/134 243/225/134
f 324/228/134 323/227/134 243/225/134
f 349/229/134 250/230/134 249/217/134
f 349/229/134 249/217/134 307/219/134
f 349/229/134 307/219/134 306/231/134
f 348/232/134 250/230/134 349/229/134
f 347/233/134 251/234/134 250/230/134
f 347/233/134 250/230/134 348/232/134
f 350/235/134 349/229/134 306/231/134
f 350/235/134 306/231/134 305/236/134
f 351/237/134 350/235/134 305/236/134
f 351/237/134 303/238/134 302/239/134
f 351/237/134 304/240/134 303/238/134
f 351/237/134 305/236/134 304/240/134
f 346/241/134 251/234/134 347/233/134
f 346/241/134 252/242/134 251/234/134
f 346/241/134 253/243/134 252/242/134
f 345/244/134 253/243/134 346/241/134
f 352/245/134 351/237/134 302/239/134
f 352/245/134 301/246/135 300/247/134
f 352/245/134 302/239/134 301/246/135
f 242/248/134 325/249/134 324/228/134
f 242/248/134 290/250/134 325/249/134
f 242/248/134 324/228/134 243/225/134
f 344/251/134 253/243/134 345/244/134
f 344/251/134 218/252/134 253/243/134
f 353/253/134 352/245/134 300/247/134
f 353/253/134 299/254/134 298/255/134
f 353/253/134 300/247/134 299/254/134
f 354/256/134 353/253/134 298/255/134
f 354/256/134 297/257/134 296/258/134
f 354/256/134 298/255/134 297/257/134
f 343/259/134 219/260/134 218/252/134
f 343/259/134 218/252/134 344/251/134
f 355/261/134 354/256/134 296/258/134
f 355/261/134 294/262/134 293/263/134
f 355/261/134 295/264/134 294/262/134
f 355/261/134 296/258/134 295/264/134
f 342/265/134 220/266/134 219/260/134
f 342/265/134 219/260/134 343/259/134
f 241/267/134 290/250/134 242/248/134
f 241/267/134 291/268/134 290/250/134
f 356/269/134 355/261/134 293/263/134
f 356/269/134 293/263/134 292/270/134
f 341/271/134 221/272/134 220/266/134
f 341/271/134 222/273/134 221/272/134
f 341/271/134 220/266/134 342/265/134
f 357/274/134 292/270/134 291/268/134
f 357/274/134 291/268/134 241/267/134
f 357/274/134 356/269/134 292/270/134
f 340/275/134 222/273/134 341/271/134
f 223/276/134 340/275/134 339/277/134
f 223/276/134 222/273/134 340/275/134
f 240/278/134 358/279/134 357/274/134
f 240/278/134 357/274/134 241/267/134
f 239/280/134 358/279/134 240/278/134
f 239/280/134 359/281/134 358/279/134
f 277/282/134 276/283/134 337/284/134
f 275/285/134 338/286/134 337/284/134
f 275/285/134 337/284/134 276/283/134
f 278/287/134 337/284/134 336/288/134
f 278/287/134 277/282/134 337/284/134
f 274/289/134 339/277/134 338/286/134
f 274/289/134 338/286/134 275/285/134
f 279/290/134 278/287/134 336/288/134
f 273/291/134 339/277/134 274/289/134
f 273/291/134 223/276/134 339/277/134
f 280/292/134 336/288/134 335/293/134
f 280/292/134 279/290/134 336/288/134
f 272/294/134 224/295/134 223/276/134
f 272/294/134 223/276/134 273/291/134
f 281/296/136 280/292/134 335/293/134
f 282/297/134 335/293/134 334/298/134
f 282/297/134 281/296/136 335/293/134
f 271/299/134 224/295/134 272/294/134
f 270/300/134 224/295/134 271/299/134
f 283/301/136 282/297/134 334/298/134
f 284/302/134 334/298/134 333/303/134
f 284/302/134 283/301/136 334/298/134
f 285/304/134 284/302/134 333/303/134
f 286/305/134 285/304/134 333/303/134
f 287/306/134 333/303/134 332/307/134
f 287/306/134 286/305/134 333/303/134
f 225/308/134 268/309/134 267/310/134
f 225/308/134 269/311/134 268/309/134
f 225/308/134 270/300/134 269/311/134
f 225/308/134 224/295/134 270/300/134
f 238/312/134 360/313/134 359/281/134
f 238/312/134 359/281/134 239/280/134
f 288/314/134 332/307/134 331/315/134
f 288/314/134 287/306/134 332/307/134
f 289/316/134 288/314/134 331/315/134
f 226/317/134 265/318/134 264/319/134
f 226/317/134 266/320/134 265/318/134
f 226/317/134 267/310/134 266/320/134
f 226/317/134 225/308/134 267/310/134
f 237/321/134 360/313/134 238/312/134
f 237/321/134 361/322/134 360/313/134
f 227/323/134 263/324/134 262/325/134
f 227/323/134 264/319/134 263/324/134
f 227/323/134 226/317/134 264/319/134
f 236/326/134 361/322/134 237/321/134
f 236/326/134 326/327/134 361/322/134
f 228/328/134 227/323/134 262/325/134
f 228/328/134 260/329/134 259/330/134
f 228/328/134 261/331/134 260/329/134
f 228/328/134 262/325/134 261/331/134
f 235/332/134 327/333/134 326/327/134
f 235/332/134 328/334/134 327/333/134
f 235/332/134 326/327/134 236/326/134
f 229/335/134 257/336/134 256/337/134
f 229/335/134 258/338/134 257/336/134
f 229/335/134 259/330/134 258/338/134
f 229/335/134 228/328/134 259/330/134
f 234/339/134 329/340/134 328/334/134
f 234/339/134 328/334/134 235/332/134
f 230/341/134 255/342/134 254/343/134
f 230/341/134 256/337/134 255/342/134
f 230/341/134 229/335/134 256/337/134
f 233/344/134 329/340/134 234/339/134
f 231/345/134 230/341/134 254/343/134
f 231/345/134 289/316/134 331/315/134
f 231/345/134 254/343/134 289/316/134
f 232/346/134 330/347/134 329/340/134
f 232/346/134 331/315/134 330/347/134
f 232/346/134 329/340/134 233/344/134
f 232/346/134 231/345/134 331/315/134
f 412/348/137 385/217/137 384/230/137
f 411/349/137 386/211/137 385/217/137
f 411/349/137 385/217/137 412/348/137
f 413/350/137 384/230/137 383/234/137
f 413/350/137 412/348/137 384/230/137
f 410/351/137 387/205/137 386/211/137
f 410/351/137 386/211/137 411/349/137
f 414/352/137 383/234/137 382/242/137
f 414/352/137 413/350/137 383/234/137
f 409/353/137 388/206/137 387/205/137
f 409/353/137 387/205/137 410/351/137
f 415/354/137 382/242/137 381/243/137
f 415/354/137 414/352/137 382/242/137
f 408/355/137 388/206/137 409/353/137
f 389/215/137 388/206/137 408/355/137
f 416/356/137 381/243/137 380/252/137
f 416/356/137 415/354/137 381/243/137
f 407/357/137 389/215/137 408/355/137
f 390/221/137 389/215/137 407/357/137
f 417/358/137 380/252/137 379/260/137
f 417/358/137 416/356/137 380/252/137
f 406/359/137 390/221/137 407/357/137
f 391/225/137 390/221/137 406/359/137
f 418/360/137 379/260/137 378/266/137
f 418/360/137 417/358/137 379/260/137
f 405/361/137 391/225/137 406/359/137
f 392/248/137 391/225/137 405/361/137
f 419/362/137 378/266/137 377/272/137
f 419/362/137 418/360/137 378/266/137
f 404/363/137 392/248/137 405/361/137
f 393/267/137 392/248/137 404/363/137
f 420/364/137 377/272/137 376/273/137
f 420/364/137 419/362/137 377/272/137
f 403/365/137 393/267/137 404/363/137
f 394/278/137 403/365/137 402/366/137
f 394/278/137 393/267/137 403/365/137
f 375/276/137 420/364/137 376/273/137
f 375/276/137 421/367/137 420/364/137
f 395/280/137 402/366/137 401/368/137
f 395/280/137 394/278/137 402/366/137
f 374/295/137 421/367/137 375/276/137
f 374/295/137 422/369/137 421/367/137
f 396/312/137 401/368/137 400/370/137
f 396/312/137 395/280/137 401/368/137
f 373/308/137 423/371/137 422/369/137
f 373/308/137 422/369/137 374/295/137
f 424/372/137 423/371/137 373/308/137
f 397/321/137 400/370/137 399/373/137
f 397/321/137 396/312/137 400/370/137
f 372/317/137 424/372/137 373/308/137
f 371/323/137 425/374/137 424/372/137
f 371/323/137 424/372/137 372/317/137
f 362/326/137 399/373/137 398/375/137
f 362/326/137 397/321/137 399/373/137
f 370/328/137 425/374/137 371/323/137
f 370/328/137 426/376/137 425/374/137
f 363/332/137 398/375/137 433/377/137
f 363/332/137 362/326/137 398/375/137
f 369/335/137 427/378/137 426/376/137
f 369/335/137 426/376/137 370/328/137
f 364/339/137 433/377/137 432/379/137
f 364/339/137 363/332/137 433/377/137
f 368/341/137 427/378/137 369/335/137
f 368/341/137 428/380/137 427/378/137
f 365/344/137 432/379/137 431/381/137
f 365/344/137 364/339/137 432/379/137
f 367/345/137 428/380/137 368/341/137
f 367/345/137 429/382/137 428/380/137
f 366/346/137 365/344/137 431/381/137
f 366/346/137 429/382/137 367/345/137
f 366/346/137 430/383/137 429/382/137
f 366/346/137 431/381/137 430/383/137
f 434/384/138 436/385/139 437/386/140
f 434/384/138 437/386/140 438/387/140
f 439/388/141 434/384/138 438/387/140
f 440/389/141 434/384/138 439/388/141
f 441/390/141 434/384/138 440/389/141
f 442/391/141 434/384/138 441/390/141
f 443/392/138 434/384/138 442/391/141
f 435/393/138 434/384/138 443/392/138
f 454/394/138 443/392/138 444/395/138
f 454/394/138 435/393/138 443/392/138
f 449/396/138 444/395/138 445/397/142
f 449/396/138 445/397/142 446/398/143
f 449/396/138 446/398/143 447/399/144
f 449/396/138 447/399/144 448/400/145
f 455/401/138 454/394/138 444/395/138
f 455/401/138 444/395/138 449/396/138
f 450/402/138 455/401/138 449/396/138
f 456/403/138 455/401/138 450/402/138
f 451/404/138 456/403/138 450/402/138
f 457/405/138 456/403/138 451/404/138
f 452/406/138 457/405/138 451/404/138
f 458/407/138 457/405/138 452/406/138
f 453/408/141 458/407/138 452/406/138
f 477/409/146 478/410/146 480/411/146
f 479/412/147 477/409/146 480/411/146
f 476/413/146 479/412/147 483/414/147
f 476/413/146 477/409/146 479/412/147
f 475/415/146 483/414/147 482/416/146
f 475/415/146 476/413/146 483/414/147
f 474/417/146 475/415/146 482/416/146
f 472/418/148 473/419/149 474/417/146
f 471/420/147 472/418/148 474/417/146
f 470/421/150 471/420/147 474/417/146
f 469/422/146 482/416/146 481/423/146
f 469/422/146 474/417/146 482/416/146
f 469/422/146 470/421/150 474/417/146
f 468/424/146 469/422/146 481/423/146
f 459/425/146 481/423/146 460/426/146
f 459/425/146 468/424/146 481/423/146
f 462/427/147 459/425/146 461/428/151
f 463/429/148 459/425/146 462/427/147
f 467/430/146 468/424/146 459/425/146
f 464/431/147 459/425/146 463/429/148
f 466/432/150 467/430/146 459/425/146
f 465/433/147 459/425/146 464/431/147
f 465/433/147 466/432/150 459/425/146
f 499/434/152 500/435/153 501/436/154
f 498/437/155 499/434/152 501/436/154
f 497/438/156 498/437/155 501/436/154
f 496/439/157 497/438/156 501/436/154
f 493/440/158 501/436/154 502/441/154
f 493/440/158 502/441/154 503/442/159
f 493/440/158 496/439/157 501/436/154
f 487/443/160 506/444/161 507/445/162
f 487/443/160 507/445/162 488/446/163
f 486/447/164 505/448/165 506/444/161
f 486/447/164 506/444/161 487/443/160
f 494/449/166 493/440/158 503/442/159
f 495/450/167 503/442/159 504/451/168
f 495/450/167 494/449/166 503/442/159
f 485/452/169 504/451/168 505/448/165
f 485/452/169 505/448/165 486/447/164
f 492/453/170 495/450/167 504/451/168
f 484/454/171 491/455/172 492/453/170
f 484/454/171 504/451/168 485/452/169
f 484/454/171 492/453/170 504/451/168
f 490/456/173 491/455/172 484/454/171
f 489/457/174 490/456/173 484/454/171
f 515/458/175 516/459/176 517/460/177
f 514/461/178 515/458/175 517/460/177
f 513/462/179 514/461/178 517/460/177
f 512/463/180 513/462/179 517/460/177
f 508/464/181 517/460/177 518/465/182
f 508/464/181 518/465/182 519/466/183
f 508/464/181 512/463/180 517/460/177
f 528/467/184 522/468/185 523/469/186
f 528/467/184 523/469/186 524/470/187
f 527/471/188 521/472/189 522/468/185
f 527/471/188 522/468/185 528/467/184
f 509/473/190 508/464/181 519/466/183
f 510/474/191 519/466/183 520/475/192
f 510/474/191 509/473/190 519/466/183
f 526/476/193 520/475/192 521/472/189
f 526/476/193 521/472/189 527/471/188
f 511/477/194 510/474/191 520/475/192
f 525/478/195 531/479/196 511/477/194
f 525/478/195 520/475/192 526/476/193
f 525/478/195 511/477/194 520/475/192
f 530/480/197 531/479/196 525/478/195
f 529/481/198 530/480/197 525/478/195
f 539/482/199 540/483/200 541/484/201
f 538/485/202 539/482/199 541/484/201
f 537/486/203 538/485/202 541/484/201
f 536/487/204 537/486/203 541/484/201
f 532/488/205 541/484/201 542/489/201
f 532/488/205 542/489/201 543/490/206
f 532/488/205 536/487/204 541/484/201
f 553/491/207 547/492/208 548/493/209
f 553/491/207 548/493/209 549/494/210
f 552/495/211 546/496/212 547/492/208
f 552/495/211 547/492/208 553/491/207
f 533/497/213 532/488/205 543/490/206
f 534/498/214 543/490/206 544/499/215
f 534/498/214 533/497/213 543/490/206
f 551/500/216 544/499/215 545/501/217
f 551/500/216 545/501/217 546/496/212
f 551/500/216 546/496/212 552/495/211
f 535/502/218 534/498/214 544/499/215
f 550/503/219 556/504/220 535/502/218
f 550/503/219 544/499/215 551/500/216
f 550/503/219 535/502/218 544/499/215
f 555/505/221 556/504/220 550/503/219
f 554/506/222 555/505/221 550/503/219
f 566/507/223 563/508/224 562/509/225
f 566/507/223 565/510/224 563/508/224
f 567/511/226 562/509/225 561/512/227
f 567/511/226 566/507/223 562/509/225
f 568/513/228 561/512/227 560/514/229
f 568/513/228 567/511/226 561/512/227
f 569/515/230 560/514/229 559/516/231
f 569/515/230 568/513/228 560/514/229
f 570/517/232 559/516/231 558/518/233
f 570/517/232 569/515/230 559/516/231
f 571/519/234 558/518/233 557/73/47
f 571/519/234 570/517/232 558/518/233
f 564/72/47 571/519/234 557/73/47
f 579/520/235 576/78/51 575/521/236
f 579/520/235 578/77/51 576/78/51
f 580/522/237 575/521/236 574/523/238
f 580/522/237 579/520/235 575/521/236
f 581/524/239 574/523/238 573/525/240
f 581/524/239 580/522/237 574/523/238
f 577/94/64 573/525/240 572/95/64
f 577/94/64 581/524/239 573/525/240
f 591/526/241 588/527/62 587/528/242
f 591/526/241 590/529/62 588/527/62
f 592/530/243 587/528/242 586/531/244
f 592/530/243 591/526/241 587/528/242
f 593/532/245 586/531/244 585/533/246
f 593/532/245 592/530/243 586/531/244
f 594/534/247 585/533/246 584/535/248
f 594/534/247 593/532/245 585/533/246
f 595/536/249 584/535/248 583/537/250
f 595/536/249 594/534/247 584/535/248
f 596/538/251 583/537/250 582/67/42
f 596/538/251 595/536/249 583/537/250
f 589/66/42 596/538/251 582/67/42
f 602/539/252 598/540/4 597/541/4
f 602/539/252 597/541/4 600/542/253
f 601/80/54 600/542/253 599/81/54
f 601/80/54 602/539/252 600/542/253
f 610/543/254 607/110/76 606/544/255
f 610/543/254 609/109/256 607/110/76
f 611/545/257 606/544/255 605/546/258
f 611/545/257 610/543/254 606/544/255
f 612/547/259 605/546/258 604/548/260
f 612/547/259 611/545/257 605/546/258
f 608/112/79 604/548/260 603/113/79
f 608/112/79 612/547/259 604/548/260
f 621/549/261 614/550/4 613/551/4
f 621/549/261 613/551/4 619/552/262
f 622/553/263 619/552/262 618/554/264
f 622/553/263 621/549/261 619/552/262
f 623/555/265 618/554/264 617/556/266
f 623/555/265 622/553/263 618/554/264
f 624/557/267 617/556/266 616/558/268
f 624/557/267 623/555/265 617/556/266
f 620/106/269 616/558/268 615/104/269
f 620/106/269 624/557/267 616/558/268
# Blender 4.3.2 MTL File: 'None'
# www.blender.org
newmtl mat_1
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_10
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_11
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_12
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_13
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_14
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_15
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_2
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_3
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_4
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_5
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_6
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_7
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_8
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_9
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
source diff could not be displayed: it is too large. Options to address this: view the blob.
source diff could not be displayed: it is too large. Options to address this: view the blob.
source diff could not be displayed: it is too large. Options to address this: view the blob.
# Blender 4.3.2 MTL File: 'None'
# www.blender.org
# Blender 4.3.2
# www.blender.org
mtllib untitled.mtl
# Exported by Open CASCADE Technology [dev.opencascade.org]
newmtl mat_1
Ka 0.220168 0.537099 0.394040
Kd 0.435294 1.000000 0.745098
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_2
Ka 0.537099 0.537099 0.537099
Kd 1.000000 1.000000 1.000000
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_3
Ka 0.352223 0.537099 0.528295
Kd 0.670588 1.000000 0.984314
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_4
Ka 0.272990 0.537099 0.407245
Kd 0.529412 1.000000 0.768627
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_5
Ka 0.398442 0.398442 0.398442
Kd 0.752941 0.752941 0.752941
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_6
Ka 0.272990 0.283995 0.283995
Kd 0.529412 0.549020 0.549020
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_7
Ka 0.101319 0.101319 0.101319
Kd 0.223529 0.223529 0.223529
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_8
Ka 0.420451 0.435857 0.499683
Kd 0.792157 0.819608 0.933333
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_9
Ka 0.000000 0.352223 0.510688
Kd 0.000000 0.670588 0.952941
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_10
Ka 0.000000 0.334615 0.484277
Kd 0.000000 0.639216 0.905882
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_11
Ka 0.482076 0.493081 0.493081
Kd 0.901961 0.921569 0.921569
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_12
Ka 0.411647 0.400643 0.389638
Kd 0.776471 0.756863 0.737255
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_13
Ka 0.255383 0.255383 0.255383
Kd 0.498039 0.498039 0.498039
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_14
Ka 0.479875 0.490880 0.497482
Kd 0.898039 0.917647 0.929412
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_15
Ka 0.385236 0.308205 0.000000
Kd 0.729412 0.592157 0.000000
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
source diff could not be displayed: it is too large. Options to address this: view the blob.
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>waterstridergazebo</name>
<version>1.0.0</version>
<description>The waterstrider description package</description>
<maintainer email="seawolfy60@gmail.com">Arina Aleevskaia</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<depend>geometry_msgs</depend>
<depend>uuv_gazebo_ros_plugins_msgs</depend>
<build_depend>eigen</build_depend>
<exec_depend>rclpy</exec_depend>
<exec_depend>gazebo_ros</exec_depend>
<exec_depend>plankton_utils</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>uuv_assistants</exec_depend>
<exec_depend>uuv_gazebo_ros_plugins</exec_depend>
<exec_depend>uuv_sensor_ros_plugins</exec_depend>
<exec_depend>xacro</exec_depend>
<exec_depend>ros2launch</exec_depend>
<exec_depend>topic_tools</exec_depend>
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>xacro</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
<?xml version="1.0"?>
<!-- Copyright (c) 2020 The Plankton Authors.
All rights reserved.
This source code is derived from UUV Simulator
(https://github.com/uuvsimulator/uuv_simulator)
Copyright (c) 2016-2019 The UUV Simulator Authors
licensed under the Apache license, Version 2.0
cf. 3rd-party-licenses.txt file in the root directory of this source tree.
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.
-->
<robot name="waterstrider" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:arg name="debug" default="0"/>
<xacro:arg name="namespace" default="waterstrider"/>
<xacro:arg name="inertial_reference_frame" default="world"/>
<!-- Include the ROV macro file -->
<xacro:include filename="$(find waterstridergazebo)/urdf/waterstrider_base.xacro"/>
<xacro:include filename="$(find waterstridergazebo)/urdf/waterstrider.gazebo.xacro"/>
<!-- Create the waterstrider -->
<xacro:waterstrider_base
namespace="$(arg namespace)"
inertial_reference_frame="$(arg inertial_reference_frame)">
<!-- The underwater object plugin is given as an input block parameter to
allow the addition of external models of manipulator units -->
<gazebo>
<plugin name="$(arg namespace)_uuv_plugin" filename="libuuv_underwater_object_ros_plugin.so">
<fluid_density>1028.0</fluid_density>
<flow_velocity_topic>hydrodynamics/current_velocity</flow_velocity_topic>
<debug>$(arg debug)</debug>
<!-- Adding the hydrodynamic and hydrostatic parameters for the vehicle-->
<xacro:waterstrider_hydro_model namespace="$(arg namespace)"/>
</plugin>
</gazebo>
</xacro:waterstrider_base>
<!-- Joint state publisher plugin -->
<xacro:default_joint_state_publisher namespace="$(arg namespace)" update_rate="50"/>
</robot>